Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Default provider is ignore #44

Merged
merged 5 commits into from
Feb 7, 2014
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ if(CATKIN_ENABLE_TESTING)
catkin_add_nosetests(test)

add_rostest(test/rostest/test_launch_manager/test_launch_manager.test)
add_rostest(test/rostest/test_server/test_default_provider.test)
add_rostest(test/rostest/test_server/test_dependent_capabilities.test)
add_rostest(test/rostest/test_server/test_invalid_specs.test)
add_rostest(test/rostest/test_server/test_package_white_black_lists.test)
Expand Down
1 change: 1 addition & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ coverage:
cd ${BUILD_DIR} && make
cd ${BUILD_DIR} && make tests
cd ${BUILD_DIR} && make run_tests
catkin_test_results ${BUILD_DIR}
ls ${HOME}/.ros/.coverage
cp ${HOME}/.ros/.coverage ./.coverage.1
cd ${BUILD_DIR} && ${BUILD_DIR}/devel/env.sh nosetests --where=${SRC_DIR}/test/unit --with-coverage -s
Expand Down
1 change: 1 addition & 0 deletions msg/CapabilityEvent.msg
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ string provider
string LAUNCHED="launched"
string STOPPED="stopped"
string TERMINATED="terminated"
string SERVER_READY="server_ready"
# Event type
string type

Expand Down
2 changes: 2 additions & 0 deletions src/capabilities/launch_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,8 @@ def handle_capability_events(self, msg):
:param msg: ROS message recieved on the events topic
:type msg: :py:class:`capabilities.msgs.CapabilityEvent`
"""
if msg.type == msg.SERVER_READY:
return
if msg.type != msg.TERMINATED:
return
with self.__running_launch_files_lock:
Expand Down
29 changes: 11 additions & 18 deletions src/capabilities/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -336,6 +336,7 @@ def spin(self):
'~events', CapabilityEvent, self.handle_capability_events)

rospy.loginfo("Capability Server Ready")
rospy.Publisher("~events", CapabilityEvent).publish(CapabilityEvent(type=CapabilityEvent.SERVER_READY))

rospy.spin()

Expand Down Expand Up @@ -597,27 +598,19 @@ def __get_capability_instances_from_provider(self, provider):
instances.append(CapabilityInstance(curr, curr_path, started_by=reason))
return instances

def __get_providers_for_interface(self, interface):
providers = dict([(n, p)
for n, p in self.__spec_index.providers.items()
if p.implements == interface])
if not providers:
raise RuntimeError("No providers for Capability '{0}'"
.format(interface))
return providers

def __start_capability(self, capability, preferred_provider):
if capability not in self.__spec_index.interfaces.keys() + self.__spec_index.semantic_interfaces.keys():
raise RuntimeError("Capability '{0}' not found.".format(capability))
providers = self.__get_providers_for_interface(capability)
if preferred_provider:
if preferred_provider not in providers:
raise RuntimeError(
"Capability Provider '{0}' not found for Capability '{1}'"
.format(preferred_provider, capability))
provider = providers[preferred_provider]
else:
provider = providers.values()[0]
# If no preferred provider is given, use the default
preferred_provider = preferred_provider or self.__default_providers[capability]
providers = dict([(n, p)
for n, p in self.__spec_index.providers.items()
if p.implements == capability])
if preferred_provider not in providers:
raise RuntimeError(
"Capability Provider '{0}' not found for Capability '{1}'"
.format(preferred_provider, capability))
provider = providers[preferred_provider]
instances = self.__get_capability_instances_from_provider(provider)
with self.__graph_lock:
for x in instances:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
<launch>
<node name="minimal" pkg="minimal_pkg" type="minimal.py" output="screen" />
<node name="minimal2" pkg="minimal_pkg" type="minimal.py" output="screen" />
</launch>
38 changes: 38 additions & 0 deletions test/rostest/test_server/test_default_provider.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#!/usr/bin/env python

from __future__ import print_function

import unittest

import rostest

import rospy

from test_ros_services import call_service
from test_ros_services import wait_for_capability_server

TEST_NAME = 'test_default_provider'


class Test(unittest.TestCase):
def test_default_provider(self):
wait_for_capability_server(None)
call_service('/capability_server/start_capability', 'no_default_provider_pkg/Minimal', '')
rospy.sleep(1) # Wait for the system to settle
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.provider for x in resp.running_capabilities]
retry_count = 0
while not result:
retry_count += 1
if retry_count == 10:
break
# Retry, sometimes the system is really slow...
rospy.sleep(1)
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.provider for x in resp.running_capabilities]
expected = ['no_default_provider_pkg/minimal']
assert sorted(result) == sorted(expected), (sorted(result), sorted(expected))

if __name__ == '__main__':
rospy.init_node(TEST_NAME, anonymous=True)
rostest.unitrun('capabilities', TEST_NAME, Test)
10 changes: 10 additions & 0 deletions test/rostest/test_server/test_default_provider.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<launch>
<node pkg="capabilities" name="capability_server" type="capability_server" output="screen" required="true"
launch-prefix="coverage run --append ">
<param name="debug" value="true"/>
<env name="ROS_PACKAGE_PATH"
value="$(find capabilities)/test/rostest/test_server/no_default_provider:$(find capabilities)/test/unit/discovery_workspaces/minimal:$(env ROS_PACKAGE_PATH)" />
<param name="defaults/no_default_provider_pkg/Minimal" value="no_default_provider_pkg/minimal" />
</node>
<test test-name="default_provider" pkg="capabilities" type="test_default_provider.py"/>
</launch>
14 changes: 14 additions & 0 deletions test/rostest/test_server/test_ros_services.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
import sys
import unittest

from threading import Event

import rostest

import rospy
Expand All @@ -24,6 +26,18 @@
from capabilities.msg import CapabilityEvent


def wait_for_capability_server(timeout=None):
event = Event()

def handler(msg):
if msg.type == msg.SERVER_READY:
event.set()

rospy.Subscriber('/capability_server/events', CapabilityEvent, handler)

return event.wait(timeout)


def call_service(service_name, *args, **kwargs):
rospy.wait_for_service(service_name)
service_type = get_service_class_by_name(service_name)
Expand Down