Skip to content

Commit

Permalink
Fix test_services.py (#653)
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Miyake <[email protected]>
  • Loading branch information
kenji-miyake authored Oct 8, 2021
1 parent 06b4ca2 commit f587a2c
Show file tree
Hide file tree
Showing 3 changed files with 54 additions and 46 deletions.
1 change: 1 addition & 0 deletions rosbridge_library/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,4 +44,5 @@ if (BUILD_TESTING)
# TODO: Enable tests
# ament_add_pytest_test(test_capabilities "test/capabilities")
# ament_add_pytest_test(test_internal "test/internal")
ament_add_pytest_test(test_services "test/internal/test_services.py")
endif()
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def args_to_service_request_instance(service, inst, args):
Propagates any exceptions that may be raised."""
msg = {}
if isinstance(args, list):
msg = dict(zip(inst.__slots__, args))
msg = dict(zip(inst.get_fields_and_field_types().keys(), args))
elif isinstance(args, dict):
msg = args

Expand Down
97 changes: 52 additions & 45 deletions rosbridge_library/test/internal/test_services.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,13 @@
import time
import unittest

import rospy
import rostest
import numpy as np
import rclpy
from rcl_interfaces.srv import ListParameters
from rclpy.node import Node
from rosbridge_library.internal import message_conversion as c
from rosbridge_library.internal import ros_loader, services
from rosbridge_library.internal.message_conversion import FieldTypeMismatchException
from roscpp.srv import GetLoggers


def populate_random_args(d):
Expand All @@ -32,32 +33,34 @@ def populate_random_args(d):
class ServiceTester:
def __init__(self, name, srv_type):
self.name = name
self.node = Node("service_tester_" + srv_type.replace("/", "_"))
self.srvClass = ros_loader.get_service_class(srv_type)
self.service = rospy.Service(name, self.srvClass, self.callback)
self.service = self.node.create_service(self.srvClass, name, self.callback)

def start(self):
req = self.srvClass._request_class()
req = self.srvClass.Request()
gen = c.extract_values(req)
gen = populate_random_args(gen)
self.input = gen
services.ServiceCaller(self.name, gen, self.success, self.error).start()
thread = services.ServiceCaller(self.name, gen, self.success, self.error, self.node)
thread.start()
thread.join()

def callback(self, req):
def callback(self, req, res):
self.req = req
time.sleep(0.5)
rsp = self.srvClass._response_class()
gen = c.extract_values(rsp)
gen = c.extract_values(res)
gen = populate_random_args(gen)
try:
rsp = c.populate_instance(gen, rsp)
res = c.populate_instance(gen, res)
except: # noqa: E722 # Will print() and raise
print("populating instance")
print(rsp)
print(res)
print("populating with")
print(gen)
raise
self.output = gen
return rsp
return res

def success(self, rsp):
self.rsp = rsp
Expand All @@ -68,15 +71,18 @@ def error(self, exc):
def validate(self, equality_function):
if hasattr(self, "exc"):
print(self.exc)
print(self.exc.message)
raise self.exc
equality_function(self.input, c.extract_values(self.req))
equality_function(self.output, self.rsp)


class TestServices(unittest.TestCase):
def setUp(self):
rospy.init_node("test_services")
rclpy.init()
self.node = Node("test_node")

def tearDown(self):
rclpy.shutdown()

def msgs_equal(self, msg1, msg2):
if isinstance(msg1, str) and isinstance(msg2, str):
Expand All @@ -86,7 +92,9 @@ def msgs_equal(self, msg1, msg2):
if type(msg1) in c.list_types:
for x, y in zip(msg1, msg2):
self.msgs_equal(x, y)
elif type(msg1) in c.primitive_types or type(msg1) in c.string_types:
elif type(msg1) in c.primitive_types or type(msg1) is str:
self.assertEqual(msg1, msg2)
elif np.issubdtype(type(msg1), np.number):
self.assertEqual(msg1, msg2)
else:
for x in msg1:
Expand All @@ -102,50 +110,57 @@ def test_populate_request_args(self):
cls = ros_loader.get_service_class("rosbridge_library/" + srv_type)
for args in [[], {}, None]:
# Should throw no exceptions
services.args_to_service_request_instance("", cls._request_class(), args)
services.args_to_service_request_instance("", cls.Request(), args)

# Test msgs with data message
for srv_type in ["TestRequestOnly", "TestRequestAndResponse"]:
cls = ros_loader.get_service_class("rosbridge_library/" + srv_type)
for args in [[3], {"data": 3}]:
# Should throw no exceptions
services.args_to_service_request_instance("", cls._request_class(), args)
services.args_to_service_request_instance("", cls.Request(), args)
self.assertRaises(
FieldTypeMismatchException,
services.args_to_service_request_instance,
"",
cls._request_class(),
cls.Request(),
["hello"],
)

# Test message with multiple fields
cls = ros_loader.get_service_class("rosbridge_library/TestMultipleRequestFields")
for args in [
[3, 3.5, "hello", False],
{"int": 3, "float": 3.5, "string": "hello", "bool": False},
{"int_value": 3, "float_value": 3.5, "string": "hello", "bool_value": False},
]:
# Should throw no exceptions
services.args_to_service_request_instance("", cls._request_class(), args)
services.args_to_service_request_instance("", cls.Request(), args)

def test_service_call(self):
"""Test a simple getloggers service call"""
"""Test a simple list_parameters service call"""
# Prepare parameter
self.node.declare_parameter("test_parameter", 1.0)

# First, call the service the 'proper' way
p = rospy.ServiceProxy(rospy.get_name() + "/get_loggers", GetLoggers)
p = self.node.create_client(ListParameters, self.node.get_name() + "/list_parameters")
p.wait_for_service(0.5)
ret = p()
ret = p.call_async(ListParameters.Request())
rclpy.spin_until_future_complete(self.node, ret)

# Now, call using the services
json_ret = services.call_service(rospy.get_name() + "/get_loggers")
for x, y in zip(ret.loggers, json_ret["loggers"]):
self.assertEqual(x.name, y["name"])
self.assertEqual(x.level, y["level"])
json_ret = services.call_service(self.node, self.node.get_name() + "/list_parameters")
for x, y in zip(ret.result().result.names, json_ret["result"]["names"]):
self.assertEqual(x, y)

def test_service_caller(self):
"""Same as test_service_call but via the thread caller"""
# Prepare parameter
self.node.declare_parameter("test_parameter", 1.0)

# First, call the service the 'proper' way
p = rospy.ServiceProxy(rospy.get_name() + "/get_loggers", GetLoggers)
p = self.node.create_client(ListParameters, self.node.get_name() + "/list_parameters")
p.wait_for_service(0.5)
ret = p()
ret = p.call_async(ListParameters.Request())
rclpy.spin_until_future_complete(self.node, ret)

rcvd = {"json": None}

Expand All @@ -156,13 +171,14 @@ def error():
raise Exception()

# Now, call using the services
services.ServiceCaller(rospy.get_name() + "/get_loggers", None, success, error).start()
services.ServiceCaller(
self.node.get_name() + "/list_parameters", None, success, error, self.node
).start()

time.sleep(0.5)

for x, y in zip(ret.loggers, rcvd["json"]["loggers"]):
self.assertEqual(x.name, y["name"])
self.assertEqual(x.level, y["level"])
for x, y in zip(ret.result().result.names, rcvd["json"]["result"]["names"]):
self.assertEqual(x, y)

def test_service_tester(self):
t = ServiceTester("/test_service_tester", "rosbridge_library/TestRequestAndResponse")
Expand Down Expand Up @@ -192,17 +208,14 @@ def test_service_tester_alltypes(self):

def test_random_service_types(self):
common = [
"roscpp/GetLoggers",
"roscpp/SetLoggerLevel",
"rcl_interfaces/ListParameters",
"rcl_interfaces/SetParameters",
"std_srvs/Empty",
"nav_msgs/GetMap",
"nav_msgs/GetPlan",
"sensor_msgs/SetCameraInfo",
"topic_tools/MuxAdd",
"topic_tools/MuxSelect",
"tf2_msgs/FrameGraph",
"rospy_tutorials/BadTwoInts",
"rospy_tutorials/AddTwoInts",
"example_interfaces/AddTwoInts",
]
ts = []
for srv in common:
Expand All @@ -214,9 +227,3 @@ def test_random_service_types(self):

for t in ts:
t.validate(self.msgs_equal)


PKG = "rosbridge_library"
NAME = "test_services"
if __name__ == "__main__":
rostest.unitrun(PKG, NAME, TestServices)

0 comments on commit f587a2c

Please sign in to comment.