Skip to content

Commit

Permalink
Replace deprecated spin_until_future_complete with spin_until_complete
Browse files Browse the repository at this point in the history
Signed-off-by: Hubert Liberacki <[email protected]>
  • Loading branch information
hliberacki committed Mar 31, 2022
1 parent 7d6f14a commit 573209c
Show file tree
Hide file tree
Showing 8 changed files with 21 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -52,17 +52,19 @@ def test_set_parameter(self, proc_output):


def set_parameter(dummy_node, value=True, timeout=5.0):
parameters = [rclpy.Parameter('demo_parameter_1', value=value).to_parameter_msg()]
parameters = [rclpy.Parameter(
'demo_parameter_1', value=value).to_parameter_msg()]

client = dummy_node.create_client(SetParameters, 'demo_node_1/set_parameters')
client = dummy_node.create_client(
SetParameters, 'demo_node_1/set_parameters')
ready = client.wait_for_service(timeout_sec=timeout)
if not ready:
raise RuntimeError('Wait for service timed out')

request = SetParameters.Request()
request.parameters = parameters
future = client.call_async(request)
rclpy.spin_until_future_complete(dummy_node, future, timeout_sec=timeout)
rclpy.spin_until_complete(dummy_node, future, timeout_sec=timeout)

response = future.result()
return response.results[0]
4 changes: 2 additions & 2 deletions rclcpp/actions/minimal_action_client/not_composable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ int main(int argc, char ** argv)
RCLCPP_INFO(node->get_logger(), "Sending goal");
// Ask server to achieve some goal and wait until it's accepted
auto goal_handle_future = action_client->async_send_goal(goal_msg);
if (rclcpp::spin_until_future_complete(node, goal_handle_future) !=
if (rclcpp::spin_until_complete(node, goal_handle_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "send goal call failed :(");
Expand All @@ -58,7 +58,7 @@ int main(int argc, char ** argv)
auto result_future = action_client->async_get_result(goal_handle);

RCLCPP_INFO(node->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node, result_future) !=
if (rclcpp::spin_until_complete(node, result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "get result call failed :(");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ int main(int argc, char ** argv)
RCLCPP_INFO(node->get_logger(), "Sending goal");
// Send goal and wait for result (registering feedback callback is optional)
auto goal_handle_future = action_client->async_send_goal(goal_msg);
if (rclcpp::spin_until_future_complete(node, goal_handle_future) !=
if (rclcpp::spin_until_complete(node, goal_handle_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "send goal call failed :(");
Expand All @@ -56,7 +56,7 @@ int main(int argc, char ** argv)
// Wait for the server to be done with the goal
auto result_future = action_client->async_get_result(goal_handle);

auto wait_result = rclcpp::spin_until_future_complete(
auto wait_result = rclcpp::spin_until_complete(
node,
result_future,
std::chrono::seconds(3));
Expand All @@ -65,7 +65,7 @@ int main(int argc, char ** argv)
RCLCPP_INFO(node->get_logger(), "canceling goal");
// Cancel the goal since it is taking too long
auto cancel_result_future = action_client->async_cancel_goal(goal_handle);
if (rclcpp::spin_until_future_complete(node, cancel_result_future) !=
if (rclcpp::spin_until_complete(node, cancel_result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "failed to cancel goal");
Expand All @@ -80,7 +80,7 @@ int main(int argc, char ** argv)
}

RCLCPP_INFO(node->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node, result_future) !=
if (rclcpp::spin_until_complete(node, result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "get result call failed :(");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ int main(int argc, char ** argv)
send_goal_options.feedback_callback = feedback_callback;
auto goal_handle_future = action_client->async_send_goal(goal_msg, send_goal_options);

if (rclcpp::spin_until_future_complete(g_node, goal_handle_future) !=
if (rclcpp::spin_until_complete(g_node, goal_handle_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(g_node->get_logger(), "send goal call failed :(");
Expand All @@ -73,7 +73,7 @@ int main(int argc, char ** argv)
auto result_future = action_client->async_get_result(goal_handle);

RCLCPP_INFO(g_node->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(g_node, result_future) !=
if (rclcpp::spin_until_complete(g_node, result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(g_node->get_logger(), "get result call failed :(");
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/services/async_client/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,7 @@ int main(int argc, char * argv[])
[stop_token = stop_async_spinner.get_future(), node]() {
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
executor.spin_until_future_complete(stop_token);
executor.spin_until_complete(stop_token);
});
while (1) {
std::string buffer;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/services/minimal_client/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ int main(int argc, char * argv[])
request->a = 41;
request->b = 1;
auto result_future = client->async_send_request(request);
if (rclcpp::spin_until_future_complete(node, result_future) !=
if (rclcpp::spin_until_complete(node, result_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "service call failed :(");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ def main(args=None):
send_goal_future = action_client.send_goal_async(
goal_msg, feedback_callback=lambda feedback: feedback_cb(node.get_logger(), feedback))

rclpy.spin_until_future_complete(node, send_goal_future)
rclpy.spin_until_complete(node, send_goal_future)

goal_handle = send_goal_future.result()

Expand All @@ -58,15 +58,16 @@ def main(args=None):

get_result_future = goal_handle.get_result_async()

rclpy.spin_until_future_complete(node, get_result_future)
rclpy.spin_until_complete(node, get_result_future)

result = get_result_future.result().result
status = get_result_future.result().status
if status == GoalStatus.STATUS_SUCCEEDED:
node.get_logger().info(
'Goal succeeded! Result: {0}'.format(result.sequence))
'Goal succeeded! Result: {0}'.format(result.sequence))
else:
node.get_logger().info('Goal failed with status code: {0}'.format(status))
node.get_logger().info(
'Goal failed with status code: {0}'.format(status))

action_client.destroy()
node.destroy_node()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def main(args=None):
node.get_logger().info('service not available, waiting again...')

future = cli.call_async(req)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)

result = future.result()
node.get_logger().info(
Expand Down

0 comments on commit 573209c

Please sign in to comment.