From 7e47aee77b7558d7d587c980cf874cbf6b2c451b Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Thu, 16 May 2024 16:36:33 -0400 Subject: [PATCH] Use a single executor instance for spinning in client_async_callback. (#382) In the current code, it calls rclpy.spin_once(), which instantiates a new executor, adds the node to it, executors one work item, then removes the node and destroys the executor. Besides being inefficient, the problem with that sequence is that adding a node to the executor actually ends up being an "event", and so the work item that gets returned can be just the work of adding the node, over and over again. For reasons I admit I don't fully understand, this only happens with rmw_cyclonedds_cpp, not with rmw_fastrtps_cpp. Regardless, the much more performant thing to do is to create an executor at the beginning of the example and to just spin on that. This eliminates adding it to the node constantly, and makes this work with all RMWs. Signed-off-by: Chris Lalancette --- .../client_async_callback.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) 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 b7d56fd9..03f3a2b6 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 @@ -26,9 +26,13 @@ def main(args=None): try: node = rclpy.create_node('minimal_client') + + executor = rclpy.executors.SingleThreadedExecutor() + executor.add_node(node) + # Node's default callback group is mutually exclusive. This would prevent the client # response from being processed until the timer callback finished, but the timer callback - # int this example is waiting for the client response + # in this example is waiting for the client response cb_group = ReentrantCallbackGroup() cli = node.create_client(AddTwoInts, 'add_two_ints', callback_group=cb_group) did_run = False @@ -55,14 +59,14 @@ async def call_service(): timer = node.create_timer(0.5, call_service, callback_group=cb_group) while rclpy.ok() and not did_run: - rclpy.spin_once(node) + executor.spin_once() if did_run: # call timer callback only once timer.cancel() while rclpy.ok() and not did_get_result: - rclpy.spin_once(node) + executor.spin_once() except KeyboardInterrupt: pass except ExternalShutdownException: