Skip to content

Commit

Permalink
Merge pull request #59 from osrf/issue_51
Browse files Browse the repository at this point in the history
Return test coverage to 100 percent
  • Loading branch information
wjwwood committed Apr 15, 2014
2 parents 76dcb8b + 026786b commit e387184
Show file tree
Hide file tree
Showing 8 changed files with 157 additions and 11 deletions.
2 changes: 2 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,9 @@ if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
catkin_add_nosetests(test)

add_rostest(test/rostest/test_client/test_client_module.test)
add_rostest(test/rostest/test_launch_manager/test_launch_manager.test)
add_rostest(test/rostest/test_server/test_client.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)
Expand Down
14 changes: 8 additions & 6 deletions src/capabilities/client.py
Original file line number Diff line number Diff line change
Expand Up @@ -149,18 +149,20 @@ def establish_bond(self, timeout=None):
to become available or while waiting for the bond to form.
:param timeout: time in seconds to wait for the service to be available
:type timeout: float
:returns: the bond_id received from the server or None on failure
:rtype: str
"""
if self.__wait_for_service(self.__establish_bond, timeout) is False:
return None
resp = self.__establish_bond()
if not resp.bond_id:
if not resp.bond_id: # pragma: no cover
return None
self._bond_id = resp.bond_id
self._bond = Bond('{0}/bonds'.format(self._name), self._bond_id)
self._bond.start()
if self._bond.wait_until_formed(rospy.Duration(timeout)) is False:
timeout_dur = None if timeout is None else rospy.Duration.from_sec(timeout)
if self._bond.wait_until_formed(timeout_dur) is False: # pragma: no cover
return None
return self._bond_id

Expand All @@ -173,7 +175,7 @@ def free_capability(self, capability_interface, timeout=None):
:param capability_interface: Name of the capability interface to free up
:type capability_interface: str
:param timeout: time to wait on service to be available (optional)
:type timeout: rospy.Duration
:type timeout: float
:returns: True if successful, otherwise False
:rtype: bool
"""
Expand Down Expand Up @@ -205,15 +207,15 @@ def use_capability(self, capability_interface, preferred_provider=None, timeout=
:param preferred_provider: preferred provider or None for default provider (optional)
:type preferred_provider: str
:param timeout: time to wait on service to be available (optional)
:type timeout: rospy.Duration
:type timeout: float
:returns: True if successful, otherwise False
:rtype: bool
"""
# If no bond has been established, establish one first
if self._bond is None:
if self.establish_bond(timeout) is None:
if self.establish_bond(timeout) is None: # pragma: no cover
return False
if self.__wait_for_service(self.__use_capability, timeout) is False:
if self.__wait_for_service(self.__use_capability, timeout) is False: # pragma: no cover
return False
self.__use_capability.call(capability_interface, preferred_provider or '', self._bond_id)
self._used_capabilities.add(capability_interface)
Expand Down
9 changes: 4 additions & 5 deletions src/capabilities/server.py
Original file line number Diff line number Diff line change
Expand Up @@ -801,7 +801,8 @@ def __free_capability(self, capability_name, bond_id):
if bond_id not in capability.bonds:
raise RuntimeError("Given bond_id '{0}' not associated with given capability '{1}'"
.format(bond_id, capability_name))
if capability.bonds[bond_id] == 0:
if capability.bonds[bond_id] == 0: # pragma: no cover
# this is defensive, it should never happen
raise RuntimeError("Cannot free capability '{0}' for bond_id '{1}', it already has a reference count of 0"
.format(capability_name, bond_id))
capability.bonds[bond_id] -= 1
Expand Down Expand Up @@ -832,10 +833,8 @@ def _handle_use_capability(self, req):
raise RuntimeError("Invalid bond_id given to ~use_capability: '{0}'".format(req.bond_id))
# Start the capability if it is not already running
if req.capability not in self.__capability_instances:
ret = self.__start_capability(req.capability, req.preferred_provider)
if not ret:
raise RuntimeError("Failed to start capability '{0}' with preferred provider '{1}'"
.format(req.capability, req.preferred_provider))
# This will raise if it failes to start the capability
self.__start_capability(req.capability, req.preferred_provider)
assert req.capability in self.__capability_instances # Should be true
# Get a handle ont he capability
capability = self.__capability_instances[req.capability]
Expand Down
34 changes: 34 additions & 0 deletions test/rostest/test_client/test_client_module.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#!/usr/bin/env python

from __future__ import print_function

# import os
# import sys
import unittest

import rostest

from capabilities.client import CapabilitiesClient

# TEST_DIR = os.path.abspath(os.path.join(os.path.dirname(__file__), '..'))

# sys.path.insert(0, TEST_DIR)
# from unit.common import assert_raises

TEST_NAME = 'test_client_module'


class Test(unittest.TestCase):
def test_client_module(self):
c = CapabilitiesClient()
c.wait_for_services(3)
c.use_capability('minimal_pkg/Minimal', 'minimal_pkg/minimal')
c.use_capability('minimal_pkg/Minimal', 'minimal_pkg/minimal')
c.free_capability('minimal_pkg/Minimal')
c.free_capability('not_a_pkg/NotACap')
c.shutdown()

if __name__ == '__main__':
import rospy
rospy.init_node(TEST_NAME, anonymous=True)
rostest.unitrun('capabilities', TEST_NAME, Test)
7 changes: 7 additions & 0 deletions test/rostest/test_client/test_client_module.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<launch>
<node pkg="capabilities" name="capability_server" type="capability_server" output="screen" required="true">
<env name="ROS_PACKAGE_PATH"
value="$(find capabilities)/test/unit/discovery_workspaces/minimal:$(env ROS_PACKAGE_PATH)" />
</node>
<test test-name="client_module" pkg="capabilities" type="test_client_module.py" launch-prefix="coverage run --source=$(find capabilities)/src/capabilities --append "/>
</launch>
80 changes: 80 additions & 0 deletions test/rostest/test_server/test_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
#!/usr/bin/env python

from __future__ import print_function

import unittest

import rostest

import rospy
from rospy.service import ServiceException

from test_ros_services import assert_raises
from test_ros_services import call_service
from test_ros_services import wait_for_capability_server

from capabilities.client import CapabilitiesClient

TEST_NAME = 'test_remapping'


def wait_for_result_to_happen(expected, initial_result, tries=10, sleep_period=1):
result = initial_result
count = 0
while count != tries and sorted(result) != sorted(expected):
rospy.sleep(sleep_period)
count += 1
resp = call_service('/capability_server/get_running_capabilities')
result = [x.capability.capability for x in resp.running_capabilities]
return result


class Test(unittest.TestCase):
def test_use_and_free_capability(self):
wait_for_capability_server(3)
c = CapabilitiesClient()
c.wait_for_services(timeout=3.0)
# Give invalid bond id to use_capability
with assert_raises(ServiceException):
call_service('/capability_server/use_capability', 'minimal_pkg/Minimal', '', 'invalid_bond_id')
# Try to use a non-existent cap
with assert_raises(ServiceException):
c.use_capability('not_a_pkg/NotACap')
# Use cap and wait for it to be running
c.use_capability('minimal_pkg/Minimal', 'minimal_pkg/minimal')
expected = ['minimal_pkg/Minimal']
result = wait_for_result_to_happen(expected, [])
assert sorted(result) == sorted(expected), (sorted(result), sorted(expected))
# Try to use it with a different provider
with assert_raises(ServiceException):
c.use_capability('minimal_pkg/Minimal', 'minimal_pkg/specific_minimal')
# Use it a second time, free it once, assert it is stil there
c.use_capability('minimal_pkg/Minimal')
c.free_capability('minimal_pkg/Minimal')
expected = []
result = wait_for_result_to_happen(expected, ['minimal_pkg/Minimal'], tries=5)
assert sorted(result) != sorted(expected), (sorted(result), sorted(expected))
# Directly call ~free_capability with an invalid bond_id
with assert_raises(ServiceException):
call_service('/capability_server/free_capability', 'minimal_pkg/Minimal', 'invalid_bond_id')
# Free it again and assert it goes down
c.free_capability('minimal_pkg/Minimal')
expected = []
result = wait_for_result_to_happen(expected, ['minimal_pkg/Minimal'])
assert sorted(result) == sorted(expected), (sorted(result), sorted(expected))
# Try to over free it and get an exception
with assert_raises(ServiceException):
c.free_capability('minimal_pkg/Minimal')
# Use it again, then break the bond and assert it goes down because of that
c.use_capability('minimal_pkg/Minimal')
expected = ['minimal_pkg/Minimal']
result = wait_for_result_to_happen(expected, [])
assert sorted(result) == sorted(expected), (sorted(result), sorted(expected))
c._bond.break_bond()
expected = []
result = wait_for_result_to_happen(expected, ['minimal_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)
9 changes: 9 additions & 0 deletions test/rostest/test_server/test_client.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<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/unit/discovery_workspaces/minimal:$(env ROS_PACKAGE_PATH)" />
</node>
<test test-name="client" pkg="capabilities" type="test_client.py"/>
</launch>
13 changes: 13 additions & 0 deletions test/unit/test_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
from common import assert_raises

from capabilities.client import CapabilitiesClient


def test_wait_for_services():
c = CapabilitiesClient()
with assert_raises(ValueError):
c.wait_for_services(0.1, ['invalid_service'])
assert c.wait_for_services(0.1) is False
c.establish_bond(0.1)
c._used_capabilities.add('some_pkg/SomeCap')
c.free_capability('some_pkg/SomeCap', 0.1)

0 comments on commit e387184

Please sign in to comment.