diff --git a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client.py b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client.py index 9f4e02e0..16ed5908 100644 --- a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client.py +++ b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client.py @@ -31,14 +31,10 @@ def main(args=None): future = cli.call_async(req) rclpy.spin_until_future_complete(node, future) - try: - result = future.result() - except Exception as e: - node.get_logger().info('Service call failed %r' % (e,)) - else: - node.get_logger().info( - 'Result of add_two_ints: for %d + %d = %d' % - (req.a, req.b, result.sum)) + result = future.result() + node.get_logger().info( + 'Result of add_two_ints: for %d + %d = %d' % + (req.a, req.b, result.sum)) node.destroy_node() rclpy.shutdown() diff --git a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async.py b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async.py index 8c808798..e154d4fa 100644 --- a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async.py +++ b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async.py @@ -34,14 +34,10 @@ def main(args=None): while rclpy.ok(): rclpy.spin_once(node) if future.done(): - try: - result = future.result() - except Exception as e: - node.get_logger().info('Service call failed %r' % (e,)) - else: - node.get_logger().info( - 'Result of add_two_ints: for %d + %d = %d' % - (req.a, req.b, result.sum)) + result = future.result() + node.get_logger().info( + 'Result of add_two_ints: for %d + %d = %d' % + (req.a, req.b, result.sum)) break node.destroy_node() diff --git a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py index ed22b6f8..7e8cd887 100644 --- a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py +++ b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py @@ -37,14 +37,10 @@ async def call_service(): req.a = 41 req.b = 1 future = cli.call_async(req) - try: - result = await future - except Exception as e: - node.get_logger().info('Service call failed %r' % (e,)) - else: - node.get_logger().info( - 'Result of add_two_ints: for %d + %d = %d' % - (req.a, req.b, result.sum)) + result = await future + node.get_logger().info( + 'Result of add_two_ints: for %d + %d = %d' % + (req.a, req.b, result.sum)) finally: did_get_result = True diff --git a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_member_function.py b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_member_function.py index 3ab910fe..ae7fc9d8 100644 --- a/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_member_function.py +++ b/rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_member_function.py @@ -42,15 +42,10 @@ def main(args=None): while rclpy.ok(): rclpy.spin_once(minimal_client) if minimal_client.future.done(): - try: - response = minimal_client.future.result() - except Exception as e: - minimal_client.get_logger().info( - 'Service call failed %r' % (e,)) - else: - minimal_client.get_logger().info( - 'Result of add_two_ints: for %d + %d = %d' % - (minimal_client.req.a, minimal_client.req.b, response.sum)) + response = minimal_client.future.result() + minimal_client.get_logger().info( + 'Result of add_two_ints: for %d + %d = %d' % + (minimal_client.req.a, minimal_client.req.b, response.sum)) break minimal_client.destroy_node()