Skip to content

Commit

Permalink
Use spin_until_complete instead of deprecated `spin_until_future_co…
Browse files Browse the repository at this point in the history
…mplete`

Signed-off-by: Hubert Liberacki <[email protected]>
  • Loading branch information
hliberacki committed Jun 3, 2022
1 parent bd49f4b commit f880a52
Show file tree
Hide file tree
Showing 6 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ int main(int argc, char ** argv)
rclcpp::Parameter("foobar", true),
});
// Wait for the result.
rclcpp::spin_until_future_complete(node, results);
rclcpp::spin_until_complete(node, results);

RCLCPP_INFO(node->get_logger(), "Listing parameters...");
// List the details of a few parameters up to a namespace depth of 10.
auto parameter_list_future = parameters_client->list_parameters({"foo", "bar"}, 10);

if (rclcpp::spin_until_future_complete(node, parameter_list_future) !=
if (rclcpp::spin_until_complete(node, parameter_list_future) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "service call failed, exiting tutorial.");
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ int main(int argc, char ** argv)

// TODO(wjwwood): Create and use delete_parameter

rclcpp::spin_until_future_complete(node, events_received_future.share());
rclcpp::spin_until_complete(node, events_received_future.share());
rclcpp::shutdown();

return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ int main(int argc, char ** argv)
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Wait for the results.
if (rclcpp::spin_until_future_complete(node, results) !=
if (rclcpp::spin_until_complete(node, results) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "set_parameters service call failed. Exiting tutorial.");
Expand All @@ -73,7 +73,7 @@ int main(int argc, char ** argv)

// Get a few of the parameters just set.
auto parameters = parameters_client->get_parameters({"foo", "baz", "foobarbaz", "toto"});
if (rclcpp::spin_until_future_complete(node, parameters) !=
if (rclcpp::spin_until_complete(node, parameters) !=
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_logger(), "get_parameters service call failed. Exiting tutorial.");
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/services/add_two_ints_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ example_interfaces::srv::AddTwoInts::Response::SharedPtr send_request(
{
auto result = client->async_send_request(request);
// Wait for the result.
if (rclcpp::spin_until_future_complete(node, result) ==
if (rclcpp::spin_until_complete(node, result) ==
rclcpp::FutureReturnCode::SUCCESS)
{
return result.get();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ def main(args=None):
req.a = 2
req.b = 3
future = cli.call_async(req)
rclpy.spin_until_future_complete(node, future)
rclpy.spin_until_complete(node, future)
if future.result() is not None:
node.get_logger().info('Result of add_two_ints: %d' % future.result().sum)
else:
Expand Down
2 changes: 1 addition & 1 deletion lifecycle/src/lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -334,7 +334,7 @@ int main(int argc, char ** argv)
std::launch::async,
std::bind(wake_executor, script, std::ref(exe)));

exe.spin_until_future_complete(script);
exe.spin_until_complete(script);

rclcpp::shutdown();

Expand Down

0 comments on commit f880a52

Please sign in to comment.