Skip to content

Commit 7e47aee

Browse files
authored
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 <[email protected]>
1 parent 65bd653 commit 7e47aee

File tree

1 file changed

+7
-3
lines changed

1 file changed

+7
-3
lines changed

rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py

+7-3
Original file line numberDiff line numberDiff line change
@@ -26,9 +26,13 @@ def main(args=None):
2626

2727
try:
2828
node = rclpy.create_node('minimal_client')
29+
30+
executor = rclpy.executors.SingleThreadedExecutor()
31+
executor.add_node(node)
32+
2933
# Node's default callback group is mutually exclusive. This would prevent the client
3034
# response from being processed until the timer callback finished, but the timer callback
31-
# int this example is waiting for the client response
35+
# in this example is waiting for the client response
3236
cb_group = ReentrantCallbackGroup()
3337
cli = node.create_client(AddTwoInts, 'add_two_ints', callback_group=cb_group)
3438
did_run = False
@@ -55,14 +59,14 @@ async def call_service():
5559
timer = node.create_timer(0.5, call_service, callback_group=cb_group)
5660

5761
while rclpy.ok() and not did_run:
58-
rclpy.spin_once(node)
62+
executor.spin_once()
5963

6064
if did_run:
6165
# call timer callback only once
6266
timer.cancel()
6367

6468
while rclpy.ok() and not did_get_result:
65-
rclpy.spin_once(node)
69+
executor.spin_once()
6670
except KeyboardInterrupt:
6771
pass
6872
except ExternalShutdownException:

0 commit comments

Comments
 (0)