Skip to content

Commit f1d7f0d

Browse files
allenh1naiveHobo
andauthored
Remove Deprecated Declaration (#1884)
* Remove deprecated rclcpp::executor::FutureReturnCode::SUCCESS in favor of rclcpp::FutureReturnCode::SUCCESS Signed-off-by: Hunter L. Allen <[email protected]> * Update nav2_util/include/nav2_util/service_client.hpp Co-authored-by: Sarthak Mittal <[email protected]> Co-authored-by: Sarthak Mittal <[email protected]>
1 parent 69fdfd6 commit f1d7f0d

File tree

8 files changed

+30
-30
lines changed

8 files changed

+30
-30
lines changed

nav2_lifecycle_manager/src/lifecycle_manager_client.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout)
8888
auto future_result = is_active_client_->async_send_request(request);
8989

9090
if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
91-
rclcpp::executor::FutureReturnCode::SUCCESS)
91+
rclcpp::FutureReturnCode::SUCCESS)
9292
{
9393
return SystemStatus::TIMEOUT;
9494
}

nav2_recoveries/test/test_recoveries.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -157,7 +157,7 @@ class RecoveryTest : public ::testing::Test
157157
auto future_goal = client_->async_send_goal(goal);
158158

159159
if (rclcpp::spin_until_future_complete(node_lifecycle_, future_goal) !=
160-
rclcpp::executor::FutureReturnCode::SUCCESS)
160+
rclcpp::FutureReturnCode::SUCCESS)
161161
{
162162
std::cout << "failed sending goal" << std::endl;
163163
// failed sending the goal

nav2_rviz_plugins/src/nav2_panel.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -410,7 +410,7 @@ Nav2Panel::onCancelButtonPressed()
410410
waypoint_follower_action_client_->async_cancel_goal(waypoint_follower_goal_handle_);
411411

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

421421
if (rclcpp::spin_until_future_complete(client_node_, future_cancel) !=
422-
rclcpp::executor::FutureReturnCode::SUCCESS)
422+
rclcpp::FutureReturnCode::SUCCESS)
423423
{
424424
RCLCPP_ERROR(client_node_->get_logger(), "Failed to cancel goal");
425425
return;
@@ -523,7 +523,7 @@ Nav2Panel::startWaypointFollowing(std::vector<geometry_msgs::msg::PoseStamped> p
523523
auto future_goal_handle =
524524
waypoint_follower_action_client_->async_send_goal(waypoint_follower_goal_, send_goal_options);
525525
if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle) !=
526-
rclcpp::executor::FutureReturnCode::SUCCESS)
526+
rclcpp::FutureReturnCode::SUCCESS)
527527
{
528528
RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
529529
return;
@@ -563,7 +563,7 @@ Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose)
563563
auto future_goal_handle =
564564
navigation_action_client_->async_send_goal(navigation_goal_, send_goal_options);
565565
if (rclcpp::spin_until_future_complete(client_node_, future_goal_handle) !=
566-
rclcpp::executor::FutureReturnCode::SUCCESS)
566+
rclcpp::FutureReturnCode::SUCCESS)
567567
{
568568
RCLCPP_ERROR(client_node_->get_logger(), "Send goal call failed");
569569
return;

nav2_system_tests/src/recoveries/backup/backup_recovery_tester.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ bool BackupRecoveryTester::defaultBackupRecoveryTest(
131131
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
132132

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

149149
RCLCPP_INFO(node_->get_logger(), "Waiting for result");
150150
if (rclcpp::spin_until_future_complete(node_, result_future) !=
151-
rclcpp::executor::FutureReturnCode::SUCCESS)
151+
rclcpp::FutureReturnCode::SUCCESS)
152152
{
153153
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
154154
return false;

nav2_system_tests/src/recoveries/spin/spin_recovery_tester.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,7 @@ bool SpinRecoveryTester::defaultSpinRecoveryTest(
129129
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
130130

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

147147
RCLCPP_INFO(node_->get_logger(), "Waiting for result");
148148
if (rclcpp::spin_until_future_complete(node_, result_future) !=
149-
rclcpp::executor::FutureReturnCode::SUCCESS)
149+
rclcpp::FutureReturnCode::SUCCESS)
150150
{
151151
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
152152
return false;

nav2_system_tests/src/recoveries/wait/wait_recovery_tester.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ bool WaitRecoveryTester::recoveryTest(
123123
auto goal_handle_future = client_ptr_->async_send_goal(goal_msg);
124124

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

141141
RCLCPP_INFO(node_->get_logger(), "Waiting for result");
142142
if (rclcpp::spin_until_future_complete(node_, result_future) !=
143-
rclcpp::executor::FutureReturnCode::SUCCESS)
143+
rclcpp::FutureReturnCode::SUCCESS)
144144
{
145145
RCLCPP_ERROR(node_->get_logger(), "get result call failed :(");
146146
return false;

nav2_util/include/nav2_util/service_client.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ class ServiceClient
7070
auto future_result = client_->async_send_request(request);
7171

7272
if (rclcpp::spin_until_future_complete(node_, future_result, timeout) !=
73-
rclcpp::executor::FutureReturnCode::SUCCESS)
73+
rclcpp::FutureReturnCode::SUCCESS)
7474
{
7575
throw std::runtime_error(service_name_ + " service client: async_send_request failed");
7676
}
@@ -98,7 +98,7 @@ class ServiceClient
9898
auto future_result = client_->async_send_request(request);
9999

100100
if (rclcpp::spin_until_future_complete(node_, future_result) !=
101-
rclcpp::executor::FutureReturnCode::SUCCESS)
101+
rclcpp::FutureReturnCode::SUCCESS)
102102
{
103103
return false;
104104
}

nav2_util/test/test_actions.cpp

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -245,15 +245,15 @@ TEST_F(ActionTest, test_simple_action)
245245
EXPECT_EQ(
246246
rclcpp::spin_until_future_complete(
247247
node_,
248-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
248+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
249249

250250
auto goal_handle = future_goal_handle.get();
251251

252252
// Wait for the result
253253
auto future_result = node_->action_client_->async_get_result(goal_handle);
254254
EXPECT_EQ(
255255
rclcpp::spin_until_future_complete(node_, future_result),
256-
rclcpp::executor::FutureReturnCode::SUCCESS);
256+
rclcpp::FutureReturnCode::SUCCESS);
257257

258258
// The final result
259259
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
@@ -293,7 +293,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback)
293293
EXPECT_EQ(
294294
rclcpp::spin_until_future_complete(
295295
node_,
296-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
296+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
297297

298298
auto goal_handle = future_goal_handle.get();
299299

@@ -302,7 +302,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback)
302302
EXPECT_EQ(
303303
rclcpp::spin_until_future_complete(
304304
node_,
305-
future_result), rclcpp::executor::FutureReturnCode::SUCCESS);
305+
future_result), rclcpp::FutureReturnCode::SUCCESS);
306306

307307
// The final result
308308
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
@@ -334,7 +334,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
334334
EXPECT_EQ(
335335
rclcpp::spin_until_future_complete(
336336
node_,
337-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
337+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
338338

339339
// Deactivate while running
340340
node_->deactivate_server();
@@ -345,7 +345,7 @@ TEST_F(ActionTest, test_simple_action_activation_cycling)
345345
auto future_result = node_->action_client_->async_get_result(goal_handle);
346346
EXPECT_EQ(
347347
rclcpp::spin_until_future_complete(node_, future_result),
348-
rclcpp::executor::FutureReturnCode::SUCCESS);
348+
rclcpp::FutureReturnCode::SUCCESS);
349349

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

366366
goal_handle = future_goal_handle.get();
367367

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

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

396396
// Preempt the goal
397397
auto preemption_goal = Fibonacci::Goal();
@@ -403,7 +403,7 @@ TEST_F(ActionTest, test_simple_action_preemption)
403403
EXPECT_EQ(
404404
rclcpp::spin_until_future_complete(
405405
node_,
406-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
406+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
407407

408408
auto goal_handle = future_goal_handle.get();
409409

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

417417
// The final result
418418
rclcpp_action::ClientGoalHandle<Fibonacci>::WrappedResult result = future_result.get();
@@ -442,15 +442,15 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
442442
EXPECT_EQ(
443443
rclcpp::spin_until_future_complete(
444444
node_,
445-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
445+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
446446

447447
node_->omit_server_preemptions();
448448

449449
auto future_preempt_handle = node_->action_client_->async_send_goal(preemption);
450450
EXPECT_EQ(
451451
rclcpp::spin_until_future_complete(
452452
node_,
453-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
453+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
454454

455455
// Get the results
456456
auto goal_handle = future_goal_handle.get();
@@ -459,7 +459,7 @@ TEST_F(ActionTest, test_simple_action_preemption_after_succeeded)
459459
auto future_result = node_->action_client_->async_get_result(goal_handle);
460460
EXPECT_EQ(
461461
rclcpp::spin_until_future_complete(node_, future_result),
462-
rclcpp::executor::FutureReturnCode::SUCCESS);
462+
rclcpp::FutureReturnCode::SUCCESS);
463463

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

485485
// The final result
486486
result = future_result.get();
@@ -507,7 +507,7 @@ TEST_F(ActionTest, test_handle_goal_deactivated)
507507
EXPECT_EQ(
508508
rclcpp::spin_until_future_complete(
509509
node_,
510-
future_goal_handle), rclcpp::executor::FutureReturnCode::SUCCESS);
510+
future_goal_handle), rclcpp::FutureReturnCode::SUCCESS);
511511

512512
node_->activate_server();
513513

0 commit comments

Comments
 (0)