Skip to content

Commit

Permalink
Merge 3367300 into 2c18dff
Browse files Browse the repository at this point in the history
  • Loading branch information
wjwwood committed Apr 1, 2014
2 parents 2c18dff + 3367300 commit 631a4a5
Show file tree
Hide file tree
Showing 18 changed files with 192 additions and 17 deletions.
1 change: 1 addition & 0 deletions Makefile
Expand Up @@ -17,6 +17,7 @@ coverage:
-rm ~/.ros/.coverage
-rm ${BUILD_DIR}/.coverage
-rm ./.coverage
-cd ${BUILD_DIR} && mkdir -p src
-ln -s ${SRC_DIR} ${BUILD_DIR}/src
cd ${BUILD_DIR} && catkin_make
cd ${BUILD_DIR} && catkin_make tests
Expand Down
1 change: 1 addition & 0 deletions launch/demo.launch
Expand Up @@ -27,5 +27,6 @@
</rosparam> -->
<!-- Uncomment below to explicitly set the default provider for minimal_pkg/Minimal -->
<!-- <param name="defaults/minimal_pkg/Minimal" value="minimal_pkg/minimal" /> -->
<param name="defaults/robot_base_pkg/Distance" value="robot_base_pkg/distance_front" />
</node>
</launch>
21 changes: 15 additions & 6 deletions src/capabilities/server.py
Expand Up @@ -644,14 +644,25 @@ 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, allow_semantic=False):
valid_interfaces = [interface]
if allow_semantic:
# Add semantic interfaces which redefine this one
valid_interfaces.extend(
[k for k, v in self.__spec_index.semantic_interfaces.items()
if v.redefines == interface]
)
providers = dict([(n, p)
for n, p in self.__spec_index.providers.items()
if p.implements in valid_interfaces])
return providers # Could be empty

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))
# 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])
providers = self.__get_providers_for_interface(capability, allow_semantic=True)
if preferred_provider not in providers:
raise RuntimeError(
"Capability Provider '{0}' not found for Capability '{1}'"
Expand Down Expand Up @@ -853,9 +864,7 @@ def _handle_get_providers(self, req):
if req.interface:
if req.interface not in self.__spec_index.interfaces.keys() + self.__spec_index.semantic_interfaces.keys():
raise RuntimeError("Capability Interface '{0}' not found.".format(req.interface))
providers = [n
for n, p in self.__spec_index.providers.items()
if p.implements == req.interface]
providers = self.__get_providers_for_interface(req.interface, allow_semantic=req.include_semantic).keys()
default_provider = self.__default_providers[req.interface]
else:
providers = self.__spec_index.provider_names
Expand Down
1 change: 1 addition & 0 deletions srv/GetProviders.srv
@@ -1,4 +1,5 @@
string interface
bool include_semantic
---
string[] providers
string default_provider
15 changes: 7 additions & 8 deletions test/rostest/test_server/test_dependent_capabilities.py
Expand Up @@ -20,16 +20,15 @@ def test_start_stop_dependent_capabilities(self):
call_service('/capability_server/start_capability',
'navigation_capability/Navigation',
'navigation_capability/faux_navigation')
rospy.sleep(6) # Wait for the system to settle
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.capability for x in resp.running_capabilities]
if not result:
# Retry, sometimes the system is really slow...
rospy.sleep(6)
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.capability for x in resp.running_capabilities]
expected = ['navigation_capability/Navigation',
'differential_mobile_base_capability/DifferentialMobileBase']
result = []
count = 0
while count != 10 and sorted(result) != sorted(expected):
rospy.sleep(1)
count += 1
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.capability for x in resp.running_capabilities]
assert sorted(result) == sorted(expected), (sorted(result), sorted(expected))
call_service('/capability_server/start_capability',
'minimal_pkg/Minimal',
Expand Down
9 changes: 6 additions & 3 deletions test/rostest/test_server/test_ros_services.py
Expand Up @@ -53,11 +53,14 @@ def test_introspection_services(self):
resp = call_service('/capability_server/get_interfaces')
assert 'minimal_pkg/Minimal' in resp.interfaces, resp
# get providers by interface
resp = call_service('/capability_server/get_providers', 'minimal_pkg/Minimal')
resp = call_service('/capability_server/get_providers', 'minimal_pkg/Minimal', False)
assert 'minimal_pkg/minimal' in resp.providers, resp
assert resp.default_provider == 'minimal_pkg/minimal', resp
assert 'minimal_pkg/specific_minimal' not in resp.providers, resp
# get providers by interface, include semantic interfaces
resp = call_service('/capability_server/get_providers', 'minimal_pkg/Minimal', True)
assert 'minimal_pkg/specific_minimal' in resp.providers, resp
# get all providers
resp = call_service('/capability_server/get_providers', '')
resp = call_service('/capability_server/get_providers', '', False)
assert 'minimal_pkg/minimal' in resp.providers, resp
assert resp.default_provider == '', resp
# fail to get providers for non-existent interface
Expand Down
@@ -0,0 +1,10 @@
%YAML 1.1
---
name: Distance
spec_version: 1
spec_type: interface
interface:
topics:
provides:
'distance':
type: 'std_msgs/Float32'
@@ -0,0 +1,9 @@
%YAML 1.1
---
name: FrontDistance
spec_version: 1
spec_type: semantic_interface
redefines: 'robot_base_pkg/Distance'
remappings:
topics:
'distance': 'front/distance'
@@ -0,0 +1,9 @@
%YAML 1.1
---
name: RearDistance
spec_version: 1
spec_type: semantic_interface
redefines: 'robot_base_pkg/Distance'
remappings:
topics:
'distance': 'rear/distance'
@@ -0,0 +1,12 @@
%YAML 1.1
---
name: RobotBase
spec_version: 1
spec_type: interface
interface:
topics:
provides:
'robot/front/distance':
type: 'std_msgs/Float32'
'robot/rear/distance':
type: 'std_msgs/Float32'
@@ -0,0 +1,41 @@
<?xml version="1.0"?>
<package>
<name>robot_base_pkg</name>
<version>0.1.0</version>
<description>desc</description>
<maintainer email="user@todo.todo">User Name</maintainer>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>

<export>
<capability_interface>
interfaces/RobotBase.yaml
</capability_interface>
<capability_interface>
interfaces/Distance.yaml
</capability_interface>
<semantic_capability_interface>
interfaces/FrontDistance.yaml
</semantic_capability_interface>
<semantic_capability_interface>
interfaces/RearDistance.yaml
</semantic_capability_interface>
<capability_provider>
providers/robot_base.yaml
</capability_provider>
<capability_provider>
providers/distance_front.yaml
</capability_provider>
<capability_provider>
providers/distance_rear.yaml
</capability_provider>
<capability_provider>
providers/front_distance.yaml
</capability_provider>
<capability_provider>
providers/rear_distance.yaml
</capability_provider>

</export>
</package>
@@ -0,0 +1,12 @@
%YAML 1.1
---
name: distance_front
spec_version: 1
spec_type: provider
implements: robot_base_pkg/Distance
depends_on:
'robot_base_pkg/RobotBase':
provider: 'robot_base_pkg/robot_base'
remappings:
topics:
'distance': 'robot/front/distance'
@@ -0,0 +1,12 @@
%YAML 1.1
---
name: distance_rear
spec_version: 1
spec_type: provider
implements: robot_base_pkg/Distance
depends_on:
'robot_base_pkg/RobotBase':
provider: 'robot_base_pkg/robot_base'
remappings:
topics:
'distance': 'robot/rear/distance'
@@ -0,0 +1,12 @@
%YAML 1.1
---
name: front_distance
spec_version: 1
spec_type: provider
implements: robot_base_pkg/FrontDistance
depends_on:
'robot_base_pkg/Distance':
provider: 'robot_base_pkg/distance_front'
remappings:
topics:
'front/distance': 'robot/front/distance'
@@ -0,0 +1,3 @@
<launch>
<node name="robot_base" pkg="robot_base_pkg" type="robot_base.py" output="screen" />
</launch>
@@ -0,0 +1,12 @@
%YAML 1.1
---
name: rear_distance
spec_version: 1
spec_type: provider
implements: robot_base_pkg/RearDistance
depends_on:
'robot_base_pkg/Distance':
provider: 'robot_base_pkg/distance_rear'
remappings:
topics:
'rear/distance': 'robot/rear/distance'
@@ -0,0 +1,7 @@
%YAML 1.1
---
name: robot_base
spec_version: 1
spec_type: provider
implements: robot_base_pkg/RobotBase
launch_file: 'launch/robot_base.launch'
@@ -0,0 +1,22 @@
#!/usr/bin/env python
import random
import time

import rospy

from std_msgs.msg import Float32


def main():
rospy.init_node('robot_base')
pub_front = rospy.Publisher('robot/front/distance', Float32)
pub_rear = rospy.Publisher('robot/rear/distance', Float32)
while not rospy.is_shutdown():
msg = Float32(random.choice([1, 2, 3, 4]))
rospy.loginfo("Sending distance: " + str(msg))
pub_front.publish(msg)
pub_rear.publish(msg)
time.sleep(1)

if __name__ == '__main__':
main()

0 comments on commit 631a4a5

Please sign in to comment.