Skip to content

Commit

Permalink
Use a single executor instance for spinning in client_async_callback. (
Browse files Browse the repository at this point in the history
…#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 <clalancette@gmail.com>
  • Loading branch information
clalancette authored May 16, 2024
1 parent 65bd653 commit 7e47aee
Showing 1 changed file with 7 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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:
Expand Down

0 comments on commit 7e47aee

Please sign in to comment.