From 04c68f54d2e4c7aa0c6f553b80457b67e2cbc1f7 Mon Sep 17 00:00:00 2001
From: Christophe Bedard <christophe.bedard@apex.ai>
Date: Tue, 2 Apr 2024 14:31:59 -0700
Subject: [PATCH] Replace deprecated `spin_until_future_complete` with
 `spin_until_complete`

Co-authored-by: Hubert Liberacki <hliberacki@gmail.com>
Signed-off-by: Hubert Liberacki <hliberacki@gmail.com>
Signed-off-by: Christophe Bedard <christophe.bedard@apex.ai>
---
 ros2action/ros2action/verb/send_goal.py     |  6 +++---
 ros2component/ros2component/api/__init__.py |  6 +++---
 ros2lifecycle/ros2lifecycle/api/__init__.py |  6 +++---
 ros2param/ros2param/api/__init__.py         | 10 +++++-----
 ros2service/ros2service/verb/call.py        |  2 +-
 ros2topic/ros2topic/verb/echo.py            |  2 +-
 ros2topic/test/test_echo_pub.py             | 16 ++++++++--------
 ros2topic/test/test_use_sim_time.py         |  6 +++---
 8 files changed, 27 insertions(+), 27 deletions(-)

diff --git a/ros2action/ros2action/verb/send_goal.py b/ros2action/ros2action/verb/send_goal.py
index 7851cd047..63f1b2906 100644
--- a/ros2action/ros2action/verb/send_goal.py
+++ b/ros2action/ros2action/verb/send_goal.py
@@ -117,7 +117,7 @@ def send_goal(action_name, action_type, goal_values, feedback_callback):
 
         print('Sending goal:\n     {}'.format(message_to_yaml(goal)))
         goal_future = action_client.send_goal_async(goal, feedback_callback)
-        rclpy.spin_until_future_complete(node, goal_future)
+        rclpy.spin_until_complete(node, goal_future)
 
         goal_handle = goal_future.result()
 
@@ -134,7 +134,7 @@ def send_goal(action_name, action_type, goal_values, feedback_callback):
         print('Goal accepted with ID: {}\n'.format(bytes(goal_handle.goal_id.uuid).hex()))
 
         result_future = goal_handle.get_result_async()
-        rclpy.spin_until_future_complete(node, result_future)
+        rclpy.spin_until_complete(node, result_future)
 
         result = result_future.result()
 
@@ -154,7 +154,7 @@ def send_goal(action_name, action_type, goal_values, feedback_callback):
              GoalStatus.STATUS_EXECUTING == goal_handle.status)):
             print('Canceling goal...')
             cancel_future = goal_handle.cancel_goal_async()
-            rclpy.spin_until_future_complete(node, cancel_future)
+            rclpy.spin_until_complete(node, cancel_future)
 
             cancel_response = cancel_future.result()
 
diff --git a/ros2component/ros2component/api/__init__.py b/ros2component/ros2component/api/__init__.py
index 1dcc0140b..69e7f6a7f 100644
--- a/ros2component/ros2component/api/__init__.py
+++ b/ros2component/ros2component/api/__init__.py
@@ -174,7 +174,7 @@ def _resume(to_completion=False):
 
     timer = node.create_timer(timer_period_sec=0.1, callback=resume)
     try:
-        rclpy.spin_until_future_complete(node, future, timeout_sec=5.0)
+        rclpy.spin_until_complete(node, future, timeout_sec=5.0)
         if not future.done():
             resume(to_completion=True)
         return dict(future.result())
@@ -244,7 +244,7 @@ def load_component_into_container(
                 arg_msg.name = name
                 request.extra_arguments.append(arg_msg)
         future = load_node_client.call_async(request)
-        rclpy.spin_until_future_complete(node, future)
+        rclpy.spin_until_complete(node, future)
         response = future.result()
         if not response.success:
             raise RuntimeError('Failed to load component: ' + response.error_message.capitalize())
@@ -274,7 +274,7 @@ def unload_component_from_container(*, node, remote_container_node_name, compone
             request = composition_interfaces.srv.UnloadNode.Request()
             request.unique_id = uid
             future = unload_node_client.call_async(request)
-            rclpy.spin_until_future_complete(node, future)
+            rclpy.spin_until_complete(node, future)
             response = future.result()
             yield uid, not response.success, response.error_message
     finally:
diff --git a/ros2lifecycle/ros2lifecycle/api/__init__.py b/ros2lifecycle/ros2lifecycle/api/__init__.py
index b1dbb5e91..6e4d216ed 100644
--- a/ros2lifecycle/ros2lifecycle/api/__init__.py
+++ b/ros2lifecycle/ros2lifecycle/api/__init__.py
@@ -67,7 +67,7 @@ def call_get_states(*, node, node_names):
 
     # wait for all responses
     for future in futures.values():
-        rclpy.spin_until_future_complete(node, future)
+        rclpy.spin_until_complete(node, future)
 
     # return current state or exception for each node
     states = {}
@@ -112,7 +112,7 @@ def _call_get_transitions(node, states, service_name):
 
     # wait for all responses
     for future in futures.values():
-        rclpy.spin_until_future_complete(node, future)
+        rclpy.spin_until_complete(node, future)
 
     # return transitions from current state or exception for each node
     transitions = {}
@@ -157,7 +157,7 @@ def call_change_states(*, node, transitions):
 
     # wait for all responses
     for future in futures.values():
-        rclpy.spin_until_future_complete(node, future)
+        rclpy.spin_until_complete(node, future)
 
     # return success flag or exception for each node
     results = {}
diff --git a/ros2param/ros2param/api/__init__.py b/ros2param/ros2param/api/__init__.py
index 7f3180492..9431255c4 100644
--- a/ros2param/ros2param/api/__init__.py
+++ b/ros2param/ros2param/api/__init__.py
@@ -40,7 +40,7 @@ def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
                            f'parameter services for node {node_name}')
     future = client.load_parameter_file(parameter_file, use_wildcard)
     parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values())
-    rclpy.spin_until_future_complete(node, future)
+    rclpy.spin_until_complete(node, future)
     response = future.result()
     assert len(response.results) == len(parameters), 'Not all parameters set'
     for i in range(0, len(response.results)):
@@ -65,7 +65,7 @@ def call_describe_parameters(*, node, node_name, parameter_names=None):
         raise RuntimeError('Wait for service timed out waiting for '
                            f'parameter services for node {node_name}')
     future = client.describe_parameters(parameter_names)
-    rclpy.spin_until_future_complete(node, future)
+    rclpy.spin_until_complete(node, future)
     response = future.result()
     if response is None:
         raise RuntimeError('Exception while calling service of node '
@@ -80,7 +80,7 @@ def call_get_parameters(*, node, node_name, parameter_names):
         raise RuntimeError('Wait for service timed out waiting for '
                            f'parameter services for node {node_name}')
     future = client.get_parameters(parameter_names)
-    rclpy.spin_until_future_complete(node, future)
+    rclpy.spin_until_complete(node, future)
     response = future.result()
     if response is None:
         raise RuntimeError('Exception while calling service of node '
@@ -95,7 +95,7 @@ def call_set_parameters(*, node, node_name, parameters):
         raise RuntimeError('Wait for service timed out waiting for '
                            f'parameter services for node {node_name}')
     future = client.set_parameters(parameters)
-    rclpy.spin_until_future_complete(node, future)
+    rclpy.spin_until_complete(node, future)
     response = future.result()
     if response is None:
         raise RuntimeError('Exception while calling service of node '
@@ -109,7 +109,7 @@ def call_list_parameters(*, node, node_name, prefixes=None):
     if not ready:
         return None
     future = client.list_parameters(prefixes=prefixes)
-    rclpy.spin_until_future_complete(node, future)
+    rclpy.spin_until_complete(node, future)
     return future
 
 
diff --git a/ros2service/ros2service/verb/call.py b/ros2service/ros2service/verb/call.py
index c5a99e865..00f5799b9 100644
--- a/ros2service/ros2service/verb/call.py
+++ b/ros2service/ros2service/verb/call.py
@@ -110,7 +110,7 @@ def requester(service_type, service_name, values, period):
         print('requester: making request: %r\n' % request)
         last_call = time.time()
         future = cli.call_async(request)
-        rclpy.spin_until_future_complete(node, future)
+        rclpy.spin_until_complete(node, future)
         if future.result() is not None:
             print('response:\n%r\n' % future.result())
         else:
diff --git a/ros2topic/ros2topic/verb/echo.py b/ros2topic/ros2topic/verb/echo.py
index 7f669c17c..c1fb67266 100644
--- a/ros2topic/ros2topic/verb/echo.py
+++ b/ros2topic/ros2topic/verb/echo.py
@@ -257,7 +257,7 @@ def subscribe_and_spin(
                 raw=raw)
 
         if self.future is not None:
-            rclpy.spin_until_future_complete(node, self.future)
+            rclpy.spin_until_complete(node, self.future)
         else:
             rclpy.spin(node)
 
diff --git a/ros2topic/test/test_echo_pub.py b/ros2topic/test/test_echo_pub.py
index 6182073e5..4741ecef0 100644
--- a/ros2topic/test/test_echo_pub.py
+++ b/ros2topic/test/test_echo_pub.py
@@ -42,8 +42,8 @@
 # https://github.com/ros2/build_farmer/issues/248
 if sys.platform.startswith('win'):
     pytest.skip(
-            'CLI tests can block for a pathological amount of time on Windows.',
-            allow_module_level=True)
+        'CLI tests can block for a pathological amount of time on Windows.',
+        allow_module_level=True)
 
 
 TEST_NODE = 'cli_echo_pub_test_node'
@@ -160,7 +160,7 @@ def message_callback(msg):
                             filtered_rmw_implementation=get_rmw_implementation_identifier()
                         )
                     ) as command:
-                        self.executor.spin_until_future_complete(future, timeout_sec=10)
+                        self.executor.spin_until_complete(future, timeout_sec=10)
                     command.wait_for_shutdown(timeout=10)
 
                     # Check results
@@ -254,7 +254,7 @@ def message_callback(msg):
                 filtered_rmw_implementation=get_rmw_implementation_identifier()
             )
         ) as command:
-            self.executor.spin_until_future_complete(future, timeout_sec=10)
+            self.executor.spin_until_complete(future, timeout_sec=10)
             assert future.done()
             assert command.wait_for_shutdown(timeout=20)
 
@@ -356,7 +356,7 @@ def publish_message():
                         )
                     ) as command:
                         # The future won't complete - we will hit the timeout
-                        self.executor.spin_until_future_complete(
+                        self.executor.spin_until_complete(
                             rclpy.task.Future(), timeout_sec=5
                         )
                     command.wait_for_shutdown(timeout=10)
@@ -414,7 +414,7 @@ def publish_message():
                         )
                     ) as command:
                         # The future won't complete - we will hit the timeout
-                        self.executor.spin_until_future_complete(
+                        self.executor.spin_until_complete(
                             rclpy.task.Future(), timeout_sec=5
                         )
                     command.wait_for_shutdown(timeout=10)
@@ -455,7 +455,7 @@ def publish_message():
                 )
             ) as command:
                 # The future won't complete - we will hit the timeout
-                self.executor.spin_until_future_complete(
+                self.executor.spin_until_complete(
                     rclpy.task.Future(), timeout_sec=5
                 )
                 assert command.wait_for_output(functools.partial(
@@ -497,7 +497,7 @@ def publish_message():
                 )
             ) as command:
                 # The future won't complete - we will hit the timeout
-                self.executor.spin_until_future_complete(
+                self.executor.spin_until_complete(
                     rclpy.task.Future(), timeout_sec=3
                 )
                 assert command.wait_for_shutdown(timeout=5)
diff --git a/ros2topic/test/test_use_sim_time.py b/ros2topic/test/test_use_sim_time.py
index 0a6b29902..e790dee46 100644
--- a/ros2topic/test/test_use_sim_time.py
+++ b/ros2topic/test/test_use_sim_time.py
@@ -118,7 +118,7 @@ def test_pub_times(self, launch_service, proc_info, proc_output):
                 )
             ) as command:
                 # The process will end up in around 2.5s (here we set 3s)
-                self.executor.spin_until_future_complete(
+                self.executor.spin_until_complete(
                     rclpy.task.Future(), timeout_sec=3
                 )
                 assert command.wait_for_shutdown(timeout=5)
@@ -183,7 +183,7 @@ def publish_message():
                 )
             ) as command:
                 # The future won't complete - we will hit the timeout
-                self.executor.spin_until_future_complete(
+                self.executor.spin_until_complete(
                     rclpy.task.Future(), timeout_sec=5
                 )
                 assert command.wait_for_output(functools.partial(
@@ -240,7 +240,7 @@ def publish_message():
                 )
             ) as command:
                 # The future won't complete - we will hit the timeout
-                self.executor.spin_until_future_complete(
+                self.executor.spin_until_complete(
                     rclpy.task.Future(), timeout_sec=10
                 )
                 assert command.wait_for_output(functools.partial(