From e14c06ed2f8c8de45181559ed007278ed343aafb Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Fri, 7 Apr 2023 17:31:20 -0700 Subject: [PATCH] ros2 service call waits forever if QoS is incompatible with concerned server https://github.com/ros2/ros2cli/issues/818 Signed-off-by: Tomoya Fujita --- prover_rclpy/setup.py | 1 + prover_rclpy/src/ros2cli_818.py | 37 +++++++++++++++++++++++++++++++++ 2 files changed, 38 insertions(+) create mode 100644 prover_rclpy/src/ros2cli_818.py diff --git a/prover_rclpy/setup.py b/prover_rclpy/setup.py index 9e85f96..6b99d56 100644 --- a/prover_rclpy/setup.py +++ b/prover_rclpy/setup.py @@ -66,6 +66,7 @@ 'rclpy_1046 = src.rclpy_1046:main', 'rclpy_1047 = src.rclpy_1047:main', 'rclpy_1098 = src.rclpy_1098:main', + 'ros2cli_818 = src.ros2cli_818:main', ], }, ) diff --git a/prover_rclpy/src/ros2cli_818.py b/prover_rclpy/src/ros2cli_818.py new file mode 100644 index 0000000..4133542 --- /dev/null +++ b/prover_rclpy/src/ros2cli_818.py @@ -0,0 +1,37 @@ +from example_interfaces.srv import AddTwoInts + +import rclpy +from rclpy.node import Node +from rclpy.qos import qos_profile_sensor_data +from rclpy.qos import qos_profile_services_default + +class ServiceProvider(Node): + + def __init__(self): + super().__init__('service_provider') + # qos_profile_sensor_data (keep_last, depth is 5 and reliability is best_effort) + # qos_profile_services_default (keep_last, depth is 10 and reliability is reliable) + self.srv = self.create_service( + #AddTwoInts, 'my_add_two_ints', self.add_two_ints_callback, qos_profile=qos_profile_services_default) + AddTwoInts, 'my_add_two_ints', self.add_two_ints_callback, qos_profile=qos_profile_sensor_data) + + def add_two_ints_callback(self, request, response): + response.sum = request.a + request.b + self.get_logger().info('Incoming request a: %d b: %d' % (request.a, request.b)) + self.get_logger().info('Outbound result : %d' % (response.sum)) + + return response + + +def main(args=None): + rclpy.init(args=args) + + service = ServiceProvider() + + rclpy.spin(service) + + rclpy.shutdown() + + +if __name__ == '__main__': + main() \ No newline at end of file