Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove Deprecated Declaration #1884

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
auto future_result = is_active_client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
return SystemStatus::TIMEOUT;
}
Expand Down
2 changes: 1 addition & 1 deletion nav2_recoveries/test/test_recoveries.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ class RecoveryTest : public ::testing::Test
auto future_goal = client_->async_send_goal(goal);

if (rclcpp::spin_until_future_complete(node_lifecycle_, future_goal) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
std::cout << "failed sending goal" << std::endl;
// failed sending the goal
Expand Down
8 changes: 4 additions & 4 deletions nav2_rviz_plugins/src/nav2_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -410,7 +410,7 @@ Nav2Panel::onCancelButtonPressed()
waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);

if (rclcpp::spin_until_future_complete(client_node_, future_cancel) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel waypoint follower");
return;
Expand All @@ -419,7 +419,7 @@ Nav2Panel::onCancelButtonPressed()
auto future_cancel = navigation_action_client_->async_cancel_goal(navigation_goal_handle_);

if (rclcpp::spin_until_future_complete(client_node_, future_cancel) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel goal");
return;
Expand Down Expand Up @@ -523,7 +523,7 @@ Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> p
auto future_goal_handle =
waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
return;
Expand Down Expand Up @@ -563,7 +563,7 @@ Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
auto future_goal_handle =
navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
return;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ bool BackupRecoveryTester::defaultBackupRecoveryTest(
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);

if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
return false;
Expand All @@ -148,7 +148,7 @@ bool BackupRecoveryTester::defaultBackupRecoveryTest(

RCLCPP_INFO(node_->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node_, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ bool SpinRecoveryTester::defaultSpinRecoveryTest(
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);

if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
return false;
Expand All @@ -146,7 +146,7 @@ bool SpinRecoveryTester::defaultSpinRecoveryTest(

RCLCPP_INFO(node_->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node_, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
return false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ bool WaitRecoveryTester::recoveryTest(
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);

if (rclcpp::spin_until_future_complete(node_, goal_handle_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "send goal call failed :(");
return false;
Expand All @@ -140,7 +140,7 @@ bool WaitRecoveryTester::recoveryTest(

RCLCPP_INFO(node_->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node_, result_future) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
return false;
Expand Down
4 changes: 2 additions & 2 deletions nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ class ServiceClient
auto future_result = client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
throw std::runtime_error(service_name_ + " service client: async_send_request failed");
}
Expand Down Expand Up @@ -98,7 +98,7 @@ class ServiceClient
auto future_result = client_->async_send_request(request);

if (rclcpp::spin_until_future_complete(node_, future_result) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
rclcpp::FutureReturnCode::SUCCESS)
{
return false;
}
Expand Down
32 changes: 16 additions & 16 deletions nav2_util/test/test_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,15 +245,15 @@ TEST_F(ActionTest, test_simple_action)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

auto goal_handle = future_goal_handle.get();

// Wait for the result
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
Expand Down Expand Up @@ -293,7 +293,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

auto goal_handle = future_goal_handle.get();

Expand All @@ -302,7 +302,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_result), rclcpp::executor::FutureReturnCode::SUCCESS);
future_result), rclcpp::FutureReturnCode::SUCCESS);

// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
Expand Down Expand Up @@ -334,7 +334,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

// Deactivate while running
node_->deactivate_server();
Expand All @@ -345,7 +345,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// The action should be reported as aborted.
EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::ABORTED);
Expand All @@ -361,7 +361,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

goal_handle = future_goal_handle.get();

Expand All @@ -370,7 +370,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
std::cout << "Getting result, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// Now the action should have been successfully executed.
EXPECT_EQ(future_result.get().code, rclcpp_action::ResultCode::SUCCEEDED);
Expand All @@ -391,7 +391,7 @@ TEST_F(ActionTest, test_simple_action_preemption)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

// Preempt the goal
auto preemption_goal = Fibonacci::Goal();
Expand All @@ -403,7 +403,7 @@ TEST_F(ActionTest, test_simple_action_preemption)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

auto goal_handle = future_goal_handle.get();

Expand All @@ -412,7 +412,7 @@ TEST_F(ActionTest, test_simple_action_preemption)
std::cout << "Getting result, spinning til complete..." << std::endl;
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
Expand Down Expand Up @@ -442,15 +442,15 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

node_->omit_server_preemptions();

auto future_preempt_handle = node_->action_client_->async_send_goal(preemption);
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

// Get the results
auto goal_handle = future_goal_handle.get();
Expand All @@ -459,7 +459,7 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
auto future_result = node_->action_client_->async_get_result(goal_handle);
EXPECT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// The final result
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
Expand All @@ -480,7 +480,7 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
future_result = node_->action_client_->async_get_result(goal_handle);
ASSERT_EQ(
rclcpp::spin_until_future_complete(node_, future_result),
rclcpp::executor::FutureReturnCode::SUCCESS);
rclcpp::FutureReturnCode::SUCCESS);

// The final result
result = future_result.get();
Expand All @@ -507,7 +507,7 @@ TEST_F(ActionTest, test_handle_goal_deactivated)
EXPECT_EQ(
rclcpp::spin_until_future_complete(
node_,
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);

node_->activate_server();

Expand Down