Skip to content

Commit

Permalink
Add rostest for service capabilities and fix bugs
Browse files Browse the repository at this point in the history
also fixed some typos
  • Loading branch information
T045T authored and Behery committed Jan 10, 2018
1 parent 950ac36 commit f0afabd
Show file tree
Hide file tree
Showing 5 changed files with 147 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@ class AdvertisedServiceHandler():
id_counter = 1
responses = {}

services_glob = None

def __init__(self, service_name, service_type, protocol):
self.service_name = service_name
self.service_type = service_type
Expand Down Expand Up @@ -49,6 +47,7 @@ def handle_request(self, req):


class AdvertiseService(Capability):
services_glob = None

advertise_service_msg_fields = [(True, "service", string_types), (True, "type", string_types)]

Expand All @@ -60,6 +59,9 @@ def __init__(self, protocol):
protocol.register_operation("advertise_service", self.advertise_service)

def advertise_service(self, message):
# Typecheck the args
self.basic_type_check(message, self.advertise_service_msg_fields)

# parse the incoming message
service_name = message["service"]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ class ServiceResponse(Capability):

service_response_msg_fields = [
(True, "service", string_types), (False, "id", string_types),
(False, "values", string_types), (True, "result", bool)
(False, "values", dict), (True, "result", bool)
]

def __init__(self, protocol):
Expand All @@ -18,6 +18,9 @@ def __init__(self, protocol):
protocol.register_operation("service_response", self.service_response)

def service_response(self, message):
# Typecheck the args
self.basic_type_check(message, self.service_response_msg_fields)

# check for the service
service_name = message["service"]
if service_name in self.protocol.external_service_list:
Expand All @@ -31,4 +34,4 @@ def service_response(self, message):
# pass along the response
service_handler.responses[request_id] = resp
else:
self.protocol.log("error", "Service %s has no been advertised externally." % service_name)
self.protocol.log("error", "Service %s has not been advertised via rosbridge." % service_name)
Original file line number Diff line number Diff line change
Expand Up @@ -39,4 +39,4 @@ def unadvertise_service(self, message):
del self.protocol.external_service_list[service_name]
self.protocol.log("info", "Unadvertised service %s." % service_name)
else:
self.protocol.log("error", "Service %s has no been advertised externally." % service_name)
self.protocol.log("error", "Service %s has not been advertised via rosbridge, can't unadvertise." % service_name)
1 change: 1 addition & 0 deletions rosbridge_library/test/capabilities/test_capabilities.test
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,5 @@
<test test-name="test_publish" pkg="rosbridge_library" type="test_publish.py" />
<test test-name="test_subscribe" pkg="rosbridge_library" type="test_subscribe.py" />
<test test-name="test_call_service" pkg="rosbridge_library" type="test_call_service.py" />
<test test-name="test_service_capabilities" pkg="rosbridge_library" type="test_service_capabilities.py" />
</launch>
136 changes: 136 additions & 0 deletions rosbridge_library/test/capabilities/test_service_capabilities.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,136 @@
#!/usr/bin/env python
import rospy
import rostest
import unittest

from json import loads, dumps

from rosbridge_library.capabilities.advertise_service import AdvertiseService
from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
from rosbridge_library.capabilities.call_service import CallService
from rosbridge_library.capabilities.service_response import ServiceResponse
from rosbridge_library.protocol import Protocol
from rosbridge_library.protocol import InvalidArgumentException, MissingArgumentException


class TestServiceCapabilities(unittest.TestCase):
def setUp(self):
self.proto = Protocol(self._testMethodName)
# change the log function so we can verify errors are logged
self.proto.log = self.mock_log
# change the send callback so we can access the rosbridge messages
# being sent
self.proto.send = self.local_send_cb
self.advertise = AdvertiseService(self.proto)
self.unadvertise = UnadvertiseService(self.proto)
self.response = ServiceResponse(self.proto)
self.received_message = None
self.log_entries = []

def local_send_cb(self, msg):
self.received_message = msg

def mock_log(self, loglevel, message, _=None):
self.log_entries.append((loglevel, message))

def test_advertise_missing_arguments(self):
advertise_msg = loads(dumps({"op": "advertise_service"}))
self.assertRaises(MissingArgumentException,
self.advertise.advertise_service, advertise_msg)

def test_advertise_invalid_arguments(self):
advertise_msg = loads(dumps({"op": "advertise_service",
"type": 42,
"service": None}))
self.assertRaises(InvalidArgumentException,
self.advertise.advertise_service, advertise_msg)

def test_response_missing_arguments(self):
response_msg = loads(dumps({"op": "service_response"}))
self.assertRaises(MissingArgumentException,
self.response.service_response, response_msg)

# this message has the optional fields, with correct types, but not the
# required ones
response_msg = loads(dumps({"op": "service_response",
"id": "dummy_service",
"values": "none"}))
self.assertRaises(MissingArgumentException,
self.response.service_response, response_msg)

def test_response_invalid_arguments(self):
response_msg = loads(dumps({"op": "service_response",
"service": 5,
"result": "error"}))
self.assertRaises(InvalidArgumentException,
self.response.service_response, response_msg)

def test_advertise_service(self):
service_path = "/set_bool_1"
advertise_msg = loads(dumps({"op": "advertise_service",
"type": "std_srvs/SetBool",
"service": service_path}))
self.advertise.advertise_service(advertise_msg)

# This throws an exception if the timeout is exceeded (i.e. the service
# is not properly advertised)
rospy.wait_for_service(service_path, 1.0)

def test_call_advertised_service(self):
service_path = "/set_bool_2"
advertise_msg = loads(dumps({"op": "advertise_service",
"type": "std_srvs/SetBool",
"service": service_path}))
self.advertise.advertise_service(advertise_msg)

# Call the service via rosbridge because rospy.ServiceProxy.call() is
# blocking
call_service = CallService(self.proto)
call_service.call_service(loads(dumps({"op": "call_service",
"id": "foo",
"service": service_path,
"args": [True]})))

loop_iterations = 0
while self.received_message is None:
rospy.sleep(rospy.Duration(0.5))
loop_iterations += 1
if loop_iterations > 3:
self.fail("did not receive service call rosbridge message "
"after waiting 2 seconds")

self.assertFalse(self.received_message is None)
self.assertTrue("op" in self.received_message)
self.assertTrue(self.received_message["op"] == "call_service")
self.assertTrue("id" in self.received_message)

# Now send the response
response_msg = loads(dumps({"op": "service_response",
"service": service_path,
"id": self.received_message["id"],
"values": {"success": True,
"message": ""},
"result": True}))
self.received_message = None
self.response.service_response(response_msg)

loop_iterations = 0
while self.received_message is None:
rospy.sleep(rospy.Duration(0.5))
loop_iterations += 1
if loop_iterations > 3:
self.fail("did not receive service response rosbridge message "
"after waiting 2 seconds")

self.assertFalse(self.received_message is None)
# Rosbridge should forward the response message to the "client"
# (i.e. our custom send function, see setUp())
self.assertEqual(self.received_message["op"], "service_response")
self.assertTrue(self.received_message["result"])


PKG = 'rosbridge_library'
NAME = 'test_service_capabilities'
if __name__ == '__main__':
rospy.init_node(NAME)
rostest.rosrun(PKG, NAME, TestServiceCapabilities)

0 comments on commit f0afabd

Please sign in to comment.