diff --git a/source/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.rst b/source/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.rst index 49aa3439c4..6b8f3d265a 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.rst @@ -661,55 +661,46 @@ Since you'll be changing the original two integer request srv to a three integer .. code-block:: python - from tutorial_interfaces.srv import AddThreeInts # CHANGE - import sys - import rclpy - from rclpy.node import Node - - - class MinimalClientAsync(Node): - - def __init__(self): - super().__init__('minimal_client_async') - self.cli = self.create_client(AddThreeInts, 'add_three_ints') # CHANGE - while not self.cli.wait_for_service(timeout_sec=1.0): - self.get_logger().info('service not available, waiting again...') - self.req = AddThreeInts.Request() # CHANGE - - def send_request(self): - self.req.a = int(sys.argv[1]) - self.req.b = int(sys.argv[2]) - self.req.c = int(sys.argv[3]) # CHANGE - self.future = self.cli.call_async(self.req) - - - def main(args=None): - rclpy.init(args=args) - - minimal_client = MinimalClientAsync() - minimal_client.send_request() - - 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_three_ints: for %d + %d + %d = %d' % # CHANGE - (minimal_client.req.a, minimal_client.req.b, minimal_client.req.c, response.sum)) # CHANGE - break - - minimal_client.destroy_node() - rclpy.shutdown() - - - if __name__ == '__main__': - main() - + import sys + + from tutorial_interfaces.srv import AddThreeInts # CHANGE + import rclpy + from rclpy.node import Node + + + class MinimalClientAsync(Node): + + def __init__(self): + super().__init__('minimal_client_async') + self.cli = self.create_client(AddThreeInts, 'add_three_ints') # CHANGE + while not self.cli.wait_for_service(timeout_sec=1.0): + self.get_logger().info('service not available, waiting again...') + self.req = AddThreeInts.Request() + + def send_request(self, a, b, c): # CHANGE + self.req.a = a + self.req.b = b + self.req.c = c # CHANGE + return self.cli.call_async(self.req) + + + def main(): + rclpy.init() + + minimal_client = MinimalClientAsync() + future = minimal_client.send_request(int(sys.argv[1]), int(sys.argv[2]), int(sys.argv[3])) # CHANGE + rclpy.spin_until_future_complete(minimal_client, future) + response = future.result() + minimal_client.get_logger().info( + 'Result of add_three_ints: for %d + %d + %d = %d' % # CHANGE + (int(sys.argv[1]), int(sys.argv[2]), int(sys.argv[3]), response.sum)) # CHANGE + + minimal_client.destroy_node() + rclpy.shutdown() + + + if __name__ == '__main__': + main() **CMakeLists.txt**