From 8a874b97a72f1fc563abe90a37501ac9c07e092c Mon Sep 17 00:00:00 2001 From: Hubert Liberacki Date: Fri, 24 Jun 2022 19:26:41 +0200 Subject: [PATCH] Replace deprecated spin_until_future_complete with spin_until_complete (#499) Signed-off-by: Hubert Liberacki --- test_communication/test/action_client_py.py | 4 +- test_communication/test/requester_py.py | 2 +- .../test/test_action_client.cpp | 4 +- .../test/test_deadline.cpp | 2 +- .../test/test_lifespan.cpp | 2 +- .../test/test_liveliness.cpp | 2 +- test_rclcpp/test/parameter_fixtures.hpp | 14 +++---- test_rclcpp/test/test_client_scope_client.cpp | 4 +- .../test_client_scope_consistency_client.cpp | 4 +- .../test/test_multiple_service_calls.cpp | 4 +- test_rclcpp/test/test_multithreaded.cpp | 2 +- test_rclcpp/test/test_services_client.cpp | 10 ++--- test_rclcpp/test/test_spin.cpp | 38 +++++++++---------- test_rclcpp/test/test_subscription.cpp | 16 ++++---- test_rclcpp/test/test_waitable.cpp | 2 +- 15 files changed, 55 insertions(+), 55 deletions(-) diff --git a/test_communication/test/action_client_py.py b/test_communication/test/action_client_py.py index 8dc8e936..f5bb4fdb 100644 --- a/test_communication/test/action_client_py.py +++ b/test_communication/test/action_client_py.py @@ -61,7 +61,7 @@ def feedback_callback(feedback): test.goal, feedback_callback=feedback_callback) - rclpy.spin_until_future_complete(node, goal_handle_future) + rclpy.spin_until_complete(node, goal_handle_future) goal_handle = goal_handle_future.result() if not goal_handle.accepted: @@ -70,7 +70,7 @@ def feedback_callback(feedback): 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() diff --git a/test_communication/test/requester_py.py b/test_communication/test/requester_py.py index 16ef2588..ba478c6c 100644 --- a/test_communication/test/requester_py.py +++ b/test_communication/test/requester_py.py @@ -45,7 +45,7 @@ def requester(service_name, namespace): # Make one call to that service for req, resp in srv_fixtures: future = client.call_async(req) - rclpy.spin_until_future_complete(node, future) + rclpy.spin_until_complete(node, future) assert repr(future.result()) == repr(resp), \ 'unexpected response %r\n\nwas expecting %r' % (future.result(), resp) print('received reply #%d of %d' % ( diff --git a/test_communication/test/test_action_client.cpp b/test_communication/test/test_action_client.cpp index 043a2578..aa0b5400 100644 --- a/test_communication/test/test_action_client.cpp +++ b/test_communication/test/test_action_client.cpp @@ -84,7 +84,7 @@ send_goals( using rclcpp::FutureReturnCode; // wait for the sent goal to be accepted - auto status = rclcpp::spin_until_future_complete(node, goal_handle_future, 1000s); + auto status = rclcpp::spin_until_complete(node, goal_handle_future, 1000s); if (status != FutureReturnCode::SUCCESS) { RCLCPP_ERROR(logger, "send goal call failed"); return 1; @@ -92,7 +92,7 @@ send_goals( // wait for the result (feedback may be received in the meantime) auto result_future = action_client->async_get_result(goal_handle_future.get()); - status = rclcpp::spin_until_future_complete(node, result_future, 1000s); + status = rclcpp::spin_until_complete(node, result_future, 1000s); if (status != FutureReturnCode::SUCCESS) { RCLCPP_ERROR(logger, "failed to receive a goal result in time"); return 1; diff --git a/test_quality_of_service/test/test_deadline.cpp b/test_quality_of_service/test/test_deadline.cpp index 89ebd765..7ea32344 100644 --- a/test_quality_of_service/test/test_deadline.cpp +++ b/test_quality_of_service/test/test_deadline.cpp @@ -97,7 +97,7 @@ TEST_F(QosRclcppTestFixture, test_deadline) { subscriber->start(); // the future will never be resolved, so simply time out to force the experiment to stop - executor->spin_until_future_complete(dummy_future, max_test_length); + executor->spin_until_complete(dummy_future, max_test_length); toggle_publisher_timer->cancel(); EXPECT_GT(publisher->get_count(), 0); // check if we published anything diff --git a/test_quality_of_service/test/test_lifespan.cpp b/test_quality_of_service/test/test_lifespan.cpp index f6e69742..0737a54d 100644 --- a/test_quality_of_service/test/test_lifespan.cpp +++ b/test_quality_of_service/test/test_lifespan.cpp @@ -76,7 +76,7 @@ TEST_F(QosRclcppTestFixture, test_lifespan) { subscriber->start(); // the future will never be resolved, so simply time out to force the experiment to stop - executor->spin_until_future_complete(dummy_future, max_test_length); + executor->spin_until_complete(dummy_future, max_test_length); toggle_subscriber_timer->cancel(); EXPECT_GT(timer_fired_count, 0); diff --git a/test_quality_of_service/test/test_liveliness.cpp b/test_quality_of_service/test/test_liveliness.cpp index 767302a6..07412d3c 100644 --- a/test_quality_of_service/test/test_liveliness.cpp +++ b/test_quality_of_service/test/test_liveliness.cpp @@ -110,7 +110,7 @@ TEST_F(QosRclcppTestFixture, test_automatic_liveliness_changed) { publisher->start(); // the future will never be resolved, so simply time out to force the experiment to stop - executor->spin_until_future_complete(dummy_future, max_test_length); + executor->spin_until_complete(dummy_future, max_test_length); kill_publisher_timer->cancel(); EXPECT_EQ(1, timer_fired_count); diff --git a/test_rclcpp/test/parameter_fixtures.hpp b/test_rclcpp/test/parameter_fixtures.hpp index 9fa77dd4..f55319dc 100644 --- a/test_rclcpp/test/parameter_fixtures.hpp +++ b/test_rclcpp/test/parameter_fixtures.hpp @@ -106,7 +106,7 @@ void test_set_parameters_async( printf("Setting parameters\n"); std::vector parameters = get_test_parameters(); auto set_parameters_results = parameters_client->set_parameters(parameters); - rclcpp::spin_until_future_complete(node, set_parameters_results); // Wait for the results. + rclcpp::spin_until_complete(node, set_parameters_results); // Wait for the results. printf("Got set_parameters result\n"); if (successful_up_to < 0 || successful_up_to > static_cast(parameters.size())) { @@ -271,7 +271,7 @@ void test_get_parameters_async( // Test recursive depth (=0) auto result = parameters_client->list_parameters( {"foo", "bar"}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE); - rclcpp::spin_until_future_complete(node, result); + rclcpp::spin_until_complete(node, result); auto parameters_and_prefixes = result.get(); for (auto & name : parameters_and_prefixes.names) { EXPECT_TRUE(name == "foo" || name == "bar" || name == "foo.first" || name == "foo.second"); @@ -283,7 +283,7 @@ void test_get_parameters_async( printf("Listing parameters with depth 1\n"); // Test different depth auto result4 = parameters_client->list_parameters({"foo"}, 1); - rclcpp::spin_until_future_complete(node, result4); + rclcpp::spin_until_complete(node, result4); auto parameters_and_prefixes4 = result4.get(); for (auto & name : parameters_and_prefixes4.names) { EXPECT_EQ(name, "foo"); @@ -295,7 +295,7 @@ void test_get_parameters_async( // Test different depth printf("Listing parameters with depth 2\n"); auto result4a = parameters_client->list_parameters({"foo"}, 2); - rclcpp::spin_until_future_complete(node, result4a); + rclcpp::spin_until_complete(node, result4a); auto parameters_and_prefixes4a = result4a.get(); for (auto & name : parameters_and_prefixes4a.names) { EXPECT_TRUE(name == "foo" || name == "foo.first" || name == "foo.second"); @@ -308,7 +308,7 @@ void test_get_parameters_async( printf("Getting parameters\n"); // Get a few of the parameters just set. auto result2 = parameters_client->get_parameters({"foo", "bar", "baz"}); - rclcpp::spin_until_future_complete(node, result2); + rclcpp::spin_until_complete(node, result2); for (auto & parameter : result2.get()) { if (parameter.get_name() == "foo") { EXPECT_STREQ("foo", parameter.get_name().c_str()); @@ -333,7 +333,7 @@ void test_get_parameters_async( // Get a few non existant parameters { auto result3 = parameters_client->get_parameters({"not_foo", "not_baz"}); - rclcpp::spin_until_future_complete(node, result3); + rclcpp::spin_until_complete(node, result3); std::vector retrieved_params = result3.get(); if (allowed_undeclared == false) { ASSERT_EQ(0u, retrieved_params.size()); @@ -350,7 +350,7 @@ void test_get_parameters_async( // List all of the parameters, using an empty prefix list auto result5 = parameters_client->list_parameters( {}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE); - rclcpp::spin_until_future_complete(node, result5); + rclcpp::spin_until_complete(node, result5); parameters_and_prefixes = result5.get(); std::vector all_names = { "foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time" diff --git a/test_rclcpp/test/test_client_scope_client.cpp b/test_rclcpp/test/test_client_scope_client.cpp index f5574247..d1e4ee8a 100644 --- a/test_rclcpp/test/test_client_scope_client.cpp +++ b/test_rclcpp/test/test_client_scope_client.cpp @@ -63,7 +63,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_te std::cout.flush(); auto result1 = client1->async_send_request(request1); if ( - rclcpp::spin_until_future_complete(node, result1) != + rclcpp::spin_until_complete(node, result1) != rclcpp::FutureReturnCode::SUCCESS) { FAIL(); @@ -90,7 +90,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_te printf("sending second request\n"); std::cout.flush(); auto result2 = client2->async_send_request(request2); - if (rclcpp::spin_until_future_complete(node, result2) != + if (rclcpp::spin_until_complete(node, result2) != rclcpp::FutureReturnCode::SUCCESS) { FAIL(); diff --git a/test_rclcpp/test/test_client_scope_consistency_client.cpp b/test_rclcpp/test/test_client_scope_consistency_client.cpp index 2278028b..82471f4e 100644 --- a/test_rclcpp/test/test_client_scope_consistency_client.cpp +++ b/test_rclcpp/test/test_client_scope_consistency_client.cpp @@ -72,7 +72,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_r std::cout.flush(); auto result1 = client1->async_send_request(request1); - ret1 = rclcpp::spin_until_future_complete(node, result1, 5s); + ret1 = rclcpp::spin_until_complete(node, result1, 5s); if (ret1 == rclcpp::FutureReturnCode::SUCCESS) { printf("received first result\n"); std::cout.flush(); @@ -108,7 +108,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_r std::cout.flush(); auto result2 = client2->async_send_request(request2); - auto ret2 = rclcpp::spin_until_future_complete(node, result2, 5s); + auto ret2 = rclcpp::spin_until_complete(node, result2, 5s); if (ret2 == rclcpp::FutureReturnCode::SUCCESS) { printf("received second result\n"); std::cout.flush(); diff --git a/test_rclcpp/test/test_multiple_service_calls.cpp b/test_rclcpp/test/test_multiple_service_calls.cpp index 85167652..a7214188 100644 --- a/test_rclcpp/test/test_multiple_service_calls.cpp +++ b/test_rclcpp/test/test_multiple_service_calls.cpp @@ -84,13 +84,13 @@ TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls) printf("Waiting for first reply...\n"); fflush(stdout); - rclcpp::spin_until_future_complete(node, result1); + rclcpp::spin_until_complete(node, result1); printf("Received first reply\n"); EXPECT_EQ(1, result1.get()->sum); printf("Waiting for second reply...\n"); fflush(stdout); - rclcpp::spin_until_future_complete(node, result2); + rclcpp::spin_until_complete(node, result2); printf("Received second reply\n"); EXPECT_EQ(2, result2.get()->sum); } diff --git a/test_rclcpp/test/test_multithreaded.cpp b/test_rclcpp/test/test_multithreaded.cpp index 3a6844f0..b65f6699 100644 --- a/test_rclcpp/test/test_multithreaded.cpp +++ b/test_rclcpp/test/test_multithreaded.cpp @@ -223,7 +223,7 @@ TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients } // Wait on each future for (uint32_t i = 0; i < results.size(); ++i) { - auto result = executor.spin_until_future_complete(results[i]); + auto result = executor.spin_until_complete(results[i]); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, result); } diff --git a/test_rclcpp/test/test_services_client.cpp b/test_rclcpp/test/test_services_client.cpp index 6e315820..ca3375f8 100644 --- a/test_rclcpp/test/test_services_client.cpp +++ b/test_rclcpp/test/test_services_client.cpp @@ -59,7 +59,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) { auto result = client->async_send_request(request); - auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. + auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(3, result.get()->sum); @@ -79,7 +79,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) { auto result = client->async_send_request(request); - auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. + auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(9, result.get()->sum); @@ -106,7 +106,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request) EXPECT_EQ(9, future.get().second->sum); }); - auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. + auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } @@ -131,7 +131,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_de EXPECT_EQ(9, future.get().second->sum); }); - auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. + auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } @@ -156,6 +156,6 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_de EXPECT_EQ(9, future.get().second->sum); }); - auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result. + auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result. ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); } diff --git a/test_rclcpp/test/test_spin.cpp b/test_rclcpp/test/test_spin.cpp index f3882f0a..6dcebad7 100644 --- a/test_rclcpp/test/test_spin.cpp +++ b/test_rclcpp/test/test_spin.cpp @@ -50,9 +50,9 @@ class CLASSNAME (test_spin, RMW_IMPLEMENTATION) : public ::testing::Test }; /* - Ensures that the timeout behavior of spin_until_future_complete is correct. + Ensures that the timeout behavior of spin_until_complete is correct. */ -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete_timeout) { +TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_complete_timeout) { using rclcpp::FutureReturnCode; rclcpp::executors::SingleThreadedExecutor executor; @@ -61,10 +61,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete std::promise already_set_promise; std::shared_future already_complete_future = already_set_promise.get_future(); already_set_promise.set_value(); - auto ret = executor.spin_until_future_complete(already_complete_future, 1s); + auto ret = executor.spin_until_complete(already_complete_future, 1s); EXPECT_EQ(FutureReturnCode::SUCCESS, ret); // Also try blocking with no timeout (default timeout of -1). - ret = executor.spin_until_future_complete(already_complete_future); + ret = executor.spin_until_complete(already_complete_future); EXPECT_EQ(FutureReturnCode::SUCCESS, ret); } @@ -73,10 +73,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete std::promise never_set_promise; std::shared_future never_complete_future = never_set_promise.get_future(); // Set the timeout just long enough to make sure it isn't incorrectly set. - auto ret = executor.spin_until_future_complete(never_complete_future, 50ms); + auto ret = executor.spin_until_complete(never_complete_future, 50ms); EXPECT_EQ(FutureReturnCode::TIMEOUT, ret); // Also try with zero timeout. - ret = executor.spin_until_future_complete(never_complete_future, 0s); + ret = executor.spin_until_complete(never_complete_future, 0s); EXPECT_EQ(FutureReturnCode::TIMEOUT, ret); } @@ -87,7 +87,7 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete []() { std::this_thread::sleep_for(50ms); }); - auto ret = executor.spin_until_future_complete(async_future, 100ms); + auto ret = executor.spin_until_complete(async_future, 100ms); EXPECT_EQ(FutureReturnCode::SUCCESS, ret); } @@ -108,10 +108,10 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete }); std::shared_future never_completed_future = never_set_promise.get_future(); // Try with a timeout long enough for both timers to fire at least once. - auto ret = executor.spin_until_future_complete(never_completed_future, 75ms); + auto ret = executor.spin_until_complete(never_completed_future, 75ms); EXPECT_EQ(FutureReturnCode::TIMEOUT, ret); // Also try with a timeout of zero (nonblocking). - ret = executor.spin_until_future_complete(never_completed_future, 0s); + ret = executor.spin_until_complete(never_completed_future, 0s); EXPECT_EQ(FutureReturnCode::TIMEOUT, ret); } @@ -129,17 +129,17 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), test_spin_until_future_complete // Do nothing. }); std::shared_future timer_fired_future = timer_fired_promise.get_future(); - auto ret = executor.spin_until_future_complete(timer_fired_future, 100ms); + auto ret = executor.spin_until_complete(timer_fired_future, 100ms); EXPECT_EQ(FutureReturnCode::SUCCESS, ret); - // Also try again with blocking spin_until_future_complete. + // Also try again with blocking spin_until_complete. timer_fired_promise = std::promise(); timer_fired_future = timer_fired_promise.get_future(); - ret = executor.spin_until_future_complete(timer_fired_future); + ret = executor.spin_until_complete(timer_fired_future); EXPECT_EQ(FutureReturnCode::SUCCESS, ret); } } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { +TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete) { auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -156,12 +156,12 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete) { rclcpp::executors::SingleThreadedExecutor executor; executor.add_node(node); ASSERT_EQ( - executor.spin_until_future_complete(future), + executor.spin_until_complete(future), rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(future.get(), true); } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_timeout) { +TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_timeout) { auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -175,18 +175,18 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_time auto timer = node->create_wall_timer(std::chrono::milliseconds(50), callback); ASSERT_EQ( - rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(25)), + rclcpp::spin_until_complete(node, future, std::chrono::milliseconds(25)), rclcpp::FutureReturnCode::TIMEOUT); // If we wait a little longer, we should complete the future ASSERT_EQ( - rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(50)), + rclcpp::spin_until_complete(node, future, std::chrono::milliseconds(50)), rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(future.get(), true); } -TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_interrupted) { +TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_interrupted) { auto node = rclcpp::Node::make_shared("test_spin"); // Construct a fake future to wait on @@ -206,7 +206,7 @@ TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_future_complete_inte auto shutdown_timer = node->create_wall_timer(std::chrono::milliseconds(25), shutdown_callback); ASSERT_EQ( - rclcpp::spin_until_future_complete(node, future, std::chrono::milliseconds(50)), + rclcpp::spin_until_complete(node, future, std::chrono::milliseconds(50)), rclcpp::FutureReturnCode::INTERRUPTED); } diff --git a/test_rclcpp/test/test_subscription.cpp b/test_rclcpp/test/test_subscription.cpp index 19ed386c..74398a8a 100644 --- a/test_rclcpp/test/test_subscription.cpp +++ b/test_rclcpp/test/test_subscription.cpp @@ -47,7 +47,7 @@ void wait_for_future( using rclcpp::FutureReturnCode; rclcpp::FutureReturnCode future_ret; auto start_time = std::chrono::steady_clock::now(); - future_ret = executor.spin_until_future_complete(future, timeout); + future_ret = executor.spin_until_complete(future, timeout); auto elapsed_time = std::chrono::steady_clock::now() - start_time; EXPECT_EQ(FutureReturnCode::SUCCESS, future_ret) << "future failed to be set after: " << @@ -117,7 +117,7 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinni ASSERT_EQ(0, counter); // spin until the subscription is called or a timeout occurs - printf("spin_until_future_complete(sub_called_future) - callback (1) expected\n"); + printf("spin_until_complete(sub_called_future) - callback (1) expected\n"); wait_for_future(executor, sub_called_future, fail_after_timeout); ASSERT_EQ(1, counter); @@ -140,28 +140,28 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinni ASSERT_EQ(1, counter); // while four messages have been published one callback should be triggered here - printf("spin_until_future_complete(short timeout) - callback (2) expected\n"); + printf("spin_until_complete(short timeout) - callback (2) expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); wait_for_future(executor, sub_called_future, 10ms); ASSERT_EQ(2, counter); // check for next pending call - printf("spin_until_future_complete(short timeout) - callback (3) expected\n"); + printf("spin_until_complete(short timeout) - callback (3) expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); wait_for_future(executor, sub_called_future, 10ms); ASSERT_EQ(3, counter); // check for next pending call - printf("spin_until_future_complete(short timeout) - callback (4) expected\n"); + printf("spin_until_complete(short timeout) - callback (4) expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); wait_for_future(executor, sub_called_future, 10ms); ASSERT_EQ(4, counter); // check for last pending call (blocking) - printf("spin_until_future_complete() - callback (5) expected\n"); + printf("spin_until_complete() - callback (5) expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); wait_for_future(executor, sub_called_future, fail_after_timeout); @@ -173,11 +173,11 @@ TEST_F(CLASSNAME(test_subscription, RMW_IMPLEMENTATION), subscription_and_spinni publisher->publish(msg); // check that no further callbacks have been invoked - printf("spin_until_future_complete(short timeout) - no callbacks expected\n"); + printf("spin_until_complete(short timeout) - no callbacks expected\n"); sub_called = std::promise(); sub_called_future = sub_called.get_future(); using rclcpp::FutureReturnCode; - FutureReturnCode future_ret = executor.spin_until_future_complete(sub_called_future, 100ms); + FutureReturnCode future_ret = executor.spin_until_complete(sub_called_future, 100ms); EXPECT_EQ(FutureReturnCode::TIMEOUT, future_ret); ASSERT_EQ(5, counter); } diff --git a/test_rclcpp/test/test_waitable.cpp b/test_rclcpp/test/test_waitable.cpp index ba0f43a5..fb05485b 100644 --- a/test_rclcpp/test/test_waitable.cpp +++ b/test_rclcpp/test/test_waitable.cpp @@ -119,7 +119,7 @@ TEST_F(CLASSNAME(test_waitable, RMW_IMPLEMENTATION), waitable_with_timer) { node->get_node_waitables_interface()->add_waitable(waitable, group); std::shared_future fut(waitable->execute_promise_.get_future()); - rclcpp::spin_until_future_complete(node, fut); + rclcpp::spin_until_complete(node, fut); EXPECT_TRUE(fut.get()); }