From 47346ef9688039b890ae19c499d4b51587a7305b Mon Sep 17 00:00:00 2001 From: Jonathan Date: Fri, 23 Aug 2024 19:06:03 -0500 Subject: [PATCH] Fixes spin_until_future_complete inside callback (#1316) Closes rclpy:#1313 Current if spin_unitl_future_complete is called inside a nodes callback it removes the node from the executor This results in any subsiquent waitables to never be checked by the node since the node is no longer in the executor This aims to fix that by only removing the node from the executor if it wasn't already present Signed-off-by: Jonathan Blixt Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com> --- rclpy/rclpy/__init__.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/rclpy/rclpy/__init__.py b/rclpy/rclpy/__init__.py index 9c43deb0a..51dc4ebda 100644 --- a/rclpy/rclpy/__init__.py +++ b/rclpy/rclpy/__init__.py @@ -331,8 +331,10 @@ def spin_until_future_complete( if ``None`` or negative. Don't wait if 0. """ executor = get_global_executor() if executor is None else executor + node_added = False try: - executor.add_node(node) + node_added = executor.add_node(node) executor.spin_until_future_complete(future, timeout_sec) finally: - executor.remove_node(node) + if node_added: + executor.remove_node(node)