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

Replace deprecated spin_until_future_complete (take 2) #541

Closed
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
4 changes: 2 additions & 2 deletions test_communication/test/action_client_py.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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()

Expand Down
2 changes: 1 addition & 1 deletion test_communication/test/requester_py.py
Original file line number Diff line number Diff line change
Expand Up @@ -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' % (
Expand Down
4 changes: 2 additions & 2 deletions test_communication/test/test_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,15 +84,15 @@ 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;
}

// 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;
Expand Down
2 changes: 1 addition & 1 deletion test_quality_of_service/test/test_deadline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion test_quality_of_service/test/test_lifespan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion test_quality_of_service/test/test_liveliness.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
12 changes: 6 additions & 6 deletions test_rclcpp/test/parameter_fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ void test_set_parameters_async(
printf("Setting parameters\n");
std::vector<rclcpp::Parameter> 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<int>(parameters.size())) {
Expand Down Expand Up @@ -268,7 +268,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");
Expand All @@ -280,7 +280,7 @@ void test_get_parameters_async(
printf("Listing parameters with depth 1 and a prefix 'foo'\n");
// Test relative depth to the given prefixes
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_TRUE(name == "foo" || name == "foo.first" || name == "foo.second");
Expand All @@ -292,7 +292,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());
Expand All @@ -317,7 +317,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<rclcpp::Parameter> retrieved_params = result3.get();
if (allowed_undeclared == false) {
ASSERT_EQ(0u, retrieved_params.size());
Expand All @@ -334,7 +334,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<std::string> all_names = {
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar"
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_client_scope_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ TEST_F(service_client, client_scope_regression_test)
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();
Expand All @@ -84,7 +84,7 @@ TEST_F(service_client, client_scope_regression_test)
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();
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_client_scope_consistency_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ TEST_F(service_client, client_scope_consistency_regression_test)
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();
Expand Down Expand Up @@ -101,7 +101,7 @@ TEST_F(service_client, client_scope_consistency_regression_test)
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();
Expand Down
4 changes: 2 additions & 2 deletions test_rclcpp/test/test_multiple_service_calls.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,13 +78,13 @@ TEST_F(test_two_service_calls, 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);
}
Expand Down
2 changes: 1 addition & 1 deletion test_rclcpp/test/test_multithreaded.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ TEST_F(test_multithreaded, 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);
}

Expand Down
10 changes: 5 additions & 5 deletions test_rclcpp/test/test_services_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ TEST_F(test_services_client, 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);
Expand All @@ -74,7 +74,7 @@ TEST_F(test_services_client, 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);
Expand Down Expand Up @@ -102,7 +102,7 @@ TEST_F(test_services_client, 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);
}

Expand All @@ -128,7 +128,7 @@ TEST_F(test_services_client, test_add_two_ints_defered_cb)
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);
}

Expand All @@ -154,6 +154,6 @@ TEST_F(test_services_client, test_add_two_ints_defcb_with_handle)
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);
}
38 changes: 19 additions & 19 deletions test_rclcpp/test/test_spin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,9 @@ class test_spin : 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(test_spin, 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;
Expand All @@ -55,10 +55,10 @@ TEST_F(test_spin, test_spin_until_future_complete_timeout)
std::promise<void> already_set_promise;
std::shared_future<void> 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);
}

Expand All @@ -67,10 +67,10 @@ TEST_F(test_spin, test_spin_until_future_complete_timeout)
std::promise<void> never_set_promise;
std::shared_future<void> 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);
}

Expand All @@ -81,7 +81,7 @@ TEST_F(test_spin, test_spin_until_future_complete_timeout)
[]() {
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);
}

Expand All @@ -102,10 +102,10 @@ TEST_F(test_spin, test_spin_until_future_complete_timeout)
});
std::shared_future<void> 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);
}

Expand All @@ -123,17 +123,17 @@ TEST_F(test_spin, test_spin_until_future_complete_timeout)
// Do nothing.
});
std::shared_future<void> 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<void>();
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(test_spin, spin_until_future_complete)
TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete)
{
auto node = rclcpp::Node::make_shared("test_spin");

Expand All @@ -151,12 +151,12 @@ TEST_F(test_spin, 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(test_spin, spin_until_future_complete_timeout)
TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_timeout)
{
auto node = rclcpp::Node::make_shared("test_spin");

Expand All @@ -171,18 +171,18 @@ TEST_F(test_spin, spin_until_future_complete_timeout)
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(test_spin, spin_until_future_complete_interrupted)
TEST_F(CLASSNAME(test_spin, RMW_IMPLEMENTATION), spin_until_complete_interrupted)
{
auto node = rclcpp::Node::make_shared("test_spin");

Expand All @@ -203,7 +203,7 @@ TEST_F(test_spin, spin_until_future_complete_interrupted)
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);
}

Expand Down
Loading