Skip to content

Commit 158ce46

Browse files
clalancettemergify[bot]
authored andcommitted
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]> (cherry picked from commit 7e47aee) # Conflicts: # rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py
1 parent 245e9a7 commit 158ce46

File tree

1 file changed

+30
-0
lines changed

1 file changed

+30
-0
lines changed

rclpy/services/minimal_client/examples_rclpy_minimal_client/client_async_callback.py

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ def main(args=None):
2929
did_run = False
3030
did_get_result = False
3131

32+
<<<<<<< HEAD
3233
async def call_service():
3334
nonlocal cli, node, did_run, did_get_result
3435
did_run = True
@@ -43,6 +44,21 @@ async def call_service():
4344
(req.a, req.b, result.sum))
4445
finally:
4546
did_get_result = True
47+
=======
48+
try:
49+
node = rclpy.create_node('minimal_client')
50+
51+
executor = rclpy.executors.SingleThreadedExecutor()
52+
executor.add_node(node)
53+
54+
# Node's default callback group is mutually exclusive. This would prevent the client
55+
# response from being processed until the timer callback finished, but the timer callback
56+
# in this example is waiting for the client response
57+
cb_group = ReentrantCallbackGroup()
58+
cli = node.create_client(AddTwoInts, 'add_two_ints', callback_group=cb_group)
59+
did_run = False
60+
did_get_result = False
61+
>>>>>>> 7e47aee (Use a single executor instance for spinning in client_async_callback. (#382))
4662

4763
while not cli.wait_for_service(timeout_sec=1.0):
4864
node.get_logger().info('service not available, waiting again...')
@@ -52,15 +68,29 @@ async def call_service():
5268
while rclpy.ok() and not did_run:
5369
rclpy.spin_once(node)
5470

71+
<<<<<<< HEAD
5572
if did_run:
5673
# call timer callback only once
5774
timer.cancel()
75+
=======
76+
while rclpy.ok() and not did_run:
77+
executor.spin_once()
78+
>>>>>>> 7e47aee (Use a single executor instance for spinning in client_async_callback. (#382))
5879

5980
while rclpy.ok() and not did_get_result:
6081
rclpy.spin_once(node)
6182

83+
<<<<<<< HEAD
6284
node.destroy_node()
6385
rclpy.shutdown()
86+
=======
87+
while rclpy.ok() and not did_get_result:
88+
executor.spin_once()
89+
except KeyboardInterrupt:
90+
pass
91+
except ExternalShutdownException:
92+
sys.exit(1)
93+
>>>>>>> 7e47aee (Use a single executor instance for spinning in client_async_callback. (#382))
6494

6595

6696
if __name__ == '__main__':

0 commit comments

Comments
 (0)