diff --git a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp index 8cb747d453a..618d318935c 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp @@ -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; } diff --git a/nav2_recoveries/test/test_recoveries.cpp b/nav2_recoveries/test/test_recoveries.cpp index a838803f87b..6f5c83912ed 100644 --- a/nav2_recoveries/test/test_recoveries.cpp +++ b/nav2_recoveries/test/test_recoveries.cpp @@ -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 diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp index 9d1b3156834..5d2b5147fc8 100644 --- a/nav2_rviz_plugins/src/nav2_panel.cpp +++ b/nav2_rviz_plugins/src/nav2_panel.cpp @@ -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; @@ -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; @@ -523,7 +523,7 @@ Nav2Panel::startWaypointFollowing(std::vector 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; @@ -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; diff --git a/nav2_system_tests/src/recoveries/backup/backup_recovery_tester.cpp b/nav2_system_tests/src/recoveries/backup/backup_recovery_tester.cpp index 6d87fb1bd28..290deff0317 100644 --- a/nav2_system_tests/src/recoveries/backup/backup_recovery_tester.cpp +++ b/nav2_system_tests/src/recoveries/backup/backup_recovery_tester.cpp @@ -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; @@ -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; diff --git a/nav2_system_tests/src/recoveries/spin/spin_recovery_tester.cpp b/nav2_system_tests/src/recoveries/spin/spin_recovery_tester.cpp index 521c6759559..ee9f6b63bc2 100644 --- a/nav2_system_tests/src/recoveries/spin/spin_recovery_tester.cpp +++ b/nav2_system_tests/src/recoveries/spin/spin_recovery_tester.cpp @@ -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; @@ -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; diff --git a/nav2_system_tests/src/recoveries/wait/wait_recovery_tester.cpp b/nav2_system_tests/src/recoveries/wait/wait_recovery_tester.cpp index b6bdd62148a..eb980e9a9d1 100644 --- a/nav2_system_tests/src/recoveries/wait/wait_recovery_tester.cpp +++ b/nav2_system_tests/src/recoveries/wait/wait_recovery_tester.cpp @@ -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; @@ -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; diff --git a/nav2_util/include/nav2_util/service_client.hpp b/nav2_util/include/nav2_util/service_client.hpp index 26f0eedf03d..e1eb6983817 100644 --- a/nav2_util/include/nav2_util/service_client.hpp +++ b/nav2_util/include/nav2_util/service_client.hpp @@ -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"); } @@ -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; } diff --git a/nav2_util/test/test_actions.cpp b/nav2_util/test/test_actions.cpp index 11d5c54f118..5619d115ebd 100644 --- a/nav2_util/test/test_actions.cpp +++ b/nav2_util/test/test_actions.cpp @@ -245,7 +245,7 @@ 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(); @@ -253,7 +253,7 @@ TEST_F(ActionTest, test_simple_action) 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::WrappedResult result = future_result.get(); @@ -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(); @@ -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::WrappedResult result = future_result.get(); @@ -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(); @@ -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); @@ -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(); @@ -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); @@ -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(); @@ -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(); @@ -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::WrappedResult result = future_result.get(); @@ -442,7 +442,7 @@ 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(); @@ -450,7 +450,7 @@ 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); // Get the results auto goal_handle = future_goal_handle.get(); @@ -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::WrappedResult result = future_result.get(); @@ -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(); @@ -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();