Skip to content

Commit

Permalink
Replace deprecated spin_until_future_complete with spin_until_complete
Browse files Browse the repository at this point in the history
Signed-off-by: Hubert Liberacki <[email protected]>
  • Loading branch information
hliberacki committed Apr 1, 2022
1 parent e29516d commit 8c7e7f0
Show file tree
Hide file tree
Showing 15 changed files with 71 additions and 63 deletions.
22 changes: 14 additions & 8 deletions test_communication/test/action_client_py.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,17 @@ def send_goals(node, action_type, tests):
import rclpy
from rclpy.action import ActionClient

action_client = ActionClient(node, action_type, 'test/action/' + action_type.__name__)
action_client = ActionClient(
node, action_type, 'test/action/' + action_type.__name__)

if not action_client.wait_for_server(20):
print('Action server not available after waiting', file=sys.stderr)
return 1

test_index = 0
while rclpy.ok() and test_index < len(tests):
print('Sending goal for test number {}'.format(test_index), file=sys.stderr)
print('Sending goal for test number {}'.format(
test_index), file=sys.stderr)

test = tests[test_index]

Expand All @@ -61,7 +63,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 +72,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 All @@ -94,7 +96,8 @@ def generate_fibonacci_goal_tests():

valid_result_sequence = [0, 1]
for i in range(1, goal.order):
valid_result_sequence.append(valid_result_sequence[i] + valid_result_sequence[i-1])
valid_result_sequence.append(
valid_result_sequence[i] + valid_result_sequence[i-1])

test = ActionClientTest(goal)

Expand Down Expand Up @@ -171,7 +174,8 @@ def is_result_valid(get_result_response):
if __name__ == '__main__':
import rclpy

parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser = argparse.ArgumentParser(
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('action_type', help='type of the ROS action')
parser.add_argument('namespace', help='namespace of the ROS node')
args = parser.parse_args()
Expand All @@ -184,9 +188,11 @@ def is_result_valid(get_result_response):
if 'Fibonacci' == args.action_type:
rc = send_goals(node, Fibonacci, generate_fibonacci_goal_tests())
elif 'NestedMessage' == args.action_type:
rc = send_goals(node, NestedMessage, generate_nested_message_goal_tests())
rc = send_goals(node, NestedMessage,
generate_nested_message_goal_tests())
else:
print('Unknown action type {!r}'.format(args.action_type), file=sys.stderr)
print('Unknown action type {!r}'.format(
args.action_type), file=sys.stderr)
except KeyboardInterrupt:
print('Action client stopped cleanly')
except ExternalShutdownException:
Expand Down
8 changes: 5 additions & 3 deletions test_communication/test/requester_py.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,10 @@ 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)
'unexpected response %r\n\nwas expecting %r' % (
future.result(), resp)
print('received reply #%d of %d' % (
srv_fixtures.index([req, resp]) + 1, len(srv_fixtures)))
finally:
Expand All @@ -57,7 +58,8 @@ def requester(service_name, namespace):


if __name__ == '__main__':
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser = argparse.ArgumentParser(
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('service_name', help='name of the ROS message')
parser.add_argument('namespace', help='namespace of the ROS node')
args = parser.parse_args()
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
14 changes: 7 additions & 7 deletions test_rclcpp/test/parameter_fixtures.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,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 @@ -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");
Expand All @@ -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");
Expand All @@ -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");
Expand All @@ -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());
Expand All @@ -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<rclcpp::Parameter> retrieved_params = result3.get();
if (allowed_undeclared == false) {
ASSERT_EQ(0u, retrieved_params.size());
Expand All @@ -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<std::string> all_names = {
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"
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 @@ -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();
Expand All @@ -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();
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 @@ -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();
Expand Down Expand Up @@ -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();
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 @@ -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);
}
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 @@ -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);
}

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 @@ -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);
Expand All @@ -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);
Expand All @@ -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);
}

Expand All @@ -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);
}

Expand All @@ -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);
}
Loading

0 comments on commit 8c7e7f0

Please sign in to comment.