Skip to content

Commit 67d88e7

Browse files
committed
Replace deprecated spin_until_future_complete with spin_until_complete
Signed-off-by: Hubert Liberacki <[email protected]>
1 parent e29516d commit 67d88e7

15 files changed

+72
-64
lines changed

test_communication/test/action_client_py.py

+14-8
Original file line numberDiff line numberDiff line change
@@ -37,15 +37,17 @@ def send_goals(node, action_type, tests):
3737
import rclpy
3838
from rclpy.action import ActionClient
3939

40-
action_client = ActionClient(node, action_type, 'test/action/' + action_type.__name__)
40+
action_client = ActionClient(
41+
node, action_type, 'test/action/' + action_type.__name__)
4142

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

4647
test_index = 0
4748
while rclpy.ok() and test_index < len(tests):
48-
print('Sending goal for test number {}'.format(test_index), file=sys.stderr)
49+
print('Sending goal for test number {}'.format(
50+
test_index), file=sys.stderr)
4951

5052
test = tests[test_index]
5153

@@ -61,7 +63,7 @@ def feedback_callback(feedback):
6163
test.goal,
6264
feedback_callback=feedback_callback)
6365

64-
rclpy.spin_until_future_complete(node, goal_handle_future)
66+
rclpy.spin_until_complete(node, goal_handle_future)
6567

6668
goal_handle = goal_handle_future.result()
6769
if not goal_handle.accepted:
@@ -70,7 +72,7 @@ def feedback_callback(feedback):
7072

7173
get_result_future = goal_handle.get_result_async()
7274

73-
rclpy.spin_until_future_complete(node, get_result_future)
75+
rclpy.spin_until_complete(node, get_result_future)
7476

7577
result = get_result_future.result()
7678

@@ -94,7 +96,8 @@ def generate_fibonacci_goal_tests():
9496

9597
valid_result_sequence = [0, 1]
9698
for i in range(1, goal.order):
97-
valid_result_sequence.append(valid_result_sequence[i] + valid_result_sequence[i-1])
99+
valid_result_sequence.append(
100+
valid_result_sequence[i] + valid_result_sequence[i-1])
98101

99102
test = ActionClientTest(goal)
100103

@@ -171,7 +174,8 @@ def is_result_valid(get_result_response):
171174
if __name__ == '__main__':
172175
import rclpy
173176

174-
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
177+
parser = argparse.ArgumentParser(
178+
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
175179
parser.add_argument('action_type', help='type of the ROS action')
176180
parser.add_argument('namespace', help='namespace of the ROS node')
177181
args = parser.parse_args()
@@ -184,9 +188,11 @@ def is_result_valid(get_result_response):
184188
if 'Fibonacci' == args.action_type:
185189
rc = send_goals(node, Fibonacci, generate_fibonacci_goal_tests())
186190
elif 'NestedMessage' == args.action_type:
187-
rc = send_goals(node, NestedMessage, generate_nested_message_goal_tests())
191+
rc = send_goals(node, NestedMessage,
192+
generate_nested_message_goal_tests())
188193
else:
189-
print('Unknown action type {!r}'.format(args.action_type), file=sys.stderr)
194+
print('Unknown action type {!r}'.format(
195+
args.action_type), file=sys.stderr)
190196
except KeyboardInterrupt:
191197
print('Action client stopped cleanly')
192198
except ExternalShutdownException:

test_communication/test/requester_py.py

+5-3
Original file line numberDiff line numberDiff line change
@@ -45,9 +45,10 @@ def requester(service_name, namespace):
4545
# Make one call to that service
4646
for req, resp in srv_fixtures:
4747
future = client.call_async(req)
48-
rclpy.spin_until_future_complete(node, future)
48+
rclpy.spin_until_complete(node, future)
4949
assert repr(future.result()) == repr(resp), \
50-
'unexpected response %r\n\nwas expecting %r' % (future.result(), resp)
50+
'unexpected response %r\n\nwas expecting %r' % (
51+
future.result(), resp)
5152
print('received reply #%d of %d' % (
5253
srv_fixtures.index([req, resp]) + 1, len(srv_fixtures)))
5354
finally:
@@ -57,7 +58,8 @@ def requester(service_name, namespace):
5758

5859

5960
if __name__ == '__main__':
60-
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
61+
parser = argparse.ArgumentParser(
62+
formatter_class=argparse.ArgumentDefaultsHelpFormatter)
6163
parser.add_argument('service_name', help='name of the ROS message')
6264
parser.add_argument('namespace', help='namespace of the ROS node')
6365
args = parser.parse_args()

test_communication/test/test_action_client.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -84,15 +84,15 @@ send_goals(
8484

8585
using rclcpp::FutureReturnCode;
8686
// wait for the sent goal to be accepted
87-
auto status = rclcpp::spin_until_future_complete(node, goal_handle_future, 1000s);
87+
auto status = rclcpp::spin_until_complete(node, goal_handle_future, 1000s);
8888
if (status != FutureReturnCode::SUCCESS) {
8989
RCLCPP_ERROR(logger, "send goal call failed");
9090
return 1;
9191
}
9292

9393
// wait for the result (feedback may be received in the meantime)
9494
auto result_future = action_client->async_get_result(goal_handle_future.get());
95-
status = rclcpp::spin_until_future_complete(node, result_future, 1000s);
95+
status = rclcpp::spin_until_complete(node, result_future, 1000s);
9696
if (status != FutureReturnCode::SUCCESS) {
9797
RCLCPP_ERROR(logger, "failed to receive a goal result in time");
9898
return 1;

test_quality_of_service/test/test_deadline.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ TEST_F(QosRclcppTestFixture, test_deadline) {
9797
subscriber->start();
9898

9999
// the future will never be resolved, so simply time out to force the experiment to stop
100-
executor->spin_until_future_complete(dummy_future, max_test_length);
100+
executor->spin_until_complete(dummy_future, max_test_length);
101101
toggle_publisher_timer->cancel();
102102

103103
EXPECT_GT(publisher->get_count(), 0); // check if we published anything

test_quality_of_service/test/test_lifespan.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,7 @@ TEST_F(QosRclcppTestFixture, test_lifespan) {
7676
subscriber->start();
7777

7878
// the future will never be resolved, so simply time out to force the experiment to stop
79-
executor->spin_until_future_complete(dummy_future, max_test_length);
79+
executor->spin_until_complete(dummy_future, max_test_length);
8080
toggle_subscriber_timer->cancel();
8181

8282
EXPECT_GT(timer_fired_count, 0);

test_quality_of_service/test/test_liveliness.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ TEST_F(QosRclcppTestFixture, test_automatic_liveliness_changed) {
110110
publisher->start();
111111

112112
// the future will never be resolved, so simply time out to force the experiment to stop
113-
executor->spin_until_future_complete(dummy_future, max_test_length);
113+
executor->spin_until_complete(dummy_future, max_test_length);
114114
kill_publisher_timer->cancel();
115115

116116
EXPECT_EQ(1, timer_fired_count);

test_rclcpp/test/parameter_fixtures.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ void test_set_parameters_async(
106106
printf("Setting parameters\n");
107107
std::vector<rclcpp::Parameter> parameters = get_test_parameters();
108108
auto set_parameters_results = parameters_client->set_parameters(parameters);
109-
rclcpp::spin_until_future_complete(node, set_parameters_results); // Wait for the results.
109+
rclcpp::spin_until_complete(node, set_parameters_results); // Wait for the results.
110110
printf("Got set_parameters result\n");
111111

112112
if (successful_up_to < 0 || successful_up_to > static_cast<int>(parameters.size())) {
@@ -271,7 +271,7 @@ void test_get_parameters_async(
271271
// Test recursive depth (=0)
272272
auto result = parameters_client->list_parameters(
273273
{"foo", "bar"}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
274-
rclcpp::spin_until_future_complete(node, result);
274+
rclcpp::spin_until_complete(node, result);
275275
auto parameters_and_prefixes = result.get();
276276
for (auto & name : parameters_and_prefixes.names) {
277277
EXPECT_TRUE(name == "foo" || name == "bar" || name == "foo.first" || name == "foo.second");
@@ -283,7 +283,7 @@ void test_get_parameters_async(
283283
printf("Listing parameters with depth 1\n");
284284
// Test different depth
285285
auto result4 = parameters_client->list_parameters({"foo"}, 1);
286-
rclcpp::spin_until_future_complete(node, result4);
286+
rclcpp::spin_until_complete(node, result4);
287287
auto parameters_and_prefixes4 = result4.get();
288288
for (auto & name : parameters_and_prefixes4.names) {
289289
EXPECT_EQ(name, "foo");
@@ -295,7 +295,7 @@ void test_get_parameters_async(
295295
// Test different depth
296296
printf("Listing parameters with depth 2\n");
297297
auto result4a = parameters_client->list_parameters({"foo"}, 2);
298-
rclcpp::spin_until_future_complete(node, result4a);
298+
rclcpp::spin_until_complete(node, result4a);
299299
auto parameters_and_prefixes4a = result4a.get();
300300
for (auto & name : parameters_and_prefixes4a.names) {
301301
EXPECT_TRUE(name == "foo" || name == "foo.first" || name == "foo.second");
@@ -308,7 +308,7 @@ void test_get_parameters_async(
308308
printf("Getting parameters\n");
309309
// Get a few of the parameters just set.
310310
auto result2 = parameters_client->get_parameters({"foo", "bar", "baz"});
311-
rclcpp::spin_until_future_complete(node, result2);
311+
rclcpp::spin_until_complete(node, result2);
312312
for (auto & parameter : result2.get()) {
313313
if (parameter.get_name() == "foo") {
314314
EXPECT_STREQ("foo", parameter.get_name().c_str());
@@ -333,7 +333,7 @@ void test_get_parameters_async(
333333
// Get a few non existant parameters
334334
{
335335
auto result3 = parameters_client->get_parameters({"not_foo", "not_baz"});
336-
rclcpp::spin_until_future_complete(node, result3);
336+
rclcpp::spin_until_complete(node, result3);
337337
std::vector<rclcpp::Parameter> retrieved_params = result3.get();
338338
if (allowed_undeclared == false) {
339339
ASSERT_EQ(0u, retrieved_params.size());
@@ -350,7 +350,7 @@ void test_get_parameters_async(
350350
// List all of the parameters, using an empty prefix list
351351
auto result5 = parameters_client->list_parameters(
352352
{}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
353-
rclcpp::spin_until_future_complete(node, result5);
353+
rclcpp::spin_until_complete(node, result5);
354354
parameters_and_prefixes = result5.get();
355355
std::vector<std::string> all_names = {
356356
"foo", "bar", "barstr", "baz", "foo.first", "foo.second", "foobar", "use_sim_time"

test_rclcpp/test/test_client_scope_client.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_te
6363
std::cout.flush();
6464
auto result1 = client1->async_send_request(request1);
6565
if (
66-
rclcpp::spin_until_future_complete(node, result1) !=
66+
rclcpp::spin_until_complete(node, result1) !=
6767
rclcpp::FutureReturnCode::SUCCESS)
6868
{
6969
FAIL();
@@ -90,7 +90,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_regression_te
9090
printf("sending second request\n");
9191
std::cout.flush();
9292
auto result2 = client2->async_send_request(request2);
93-
if (rclcpp::spin_until_future_complete(node, result2) !=
93+
if (rclcpp::spin_until_complete(node, result2) !=
9494
rclcpp::FutureReturnCode::SUCCESS)
9595
{
9696
FAIL();

test_rclcpp/test/test_client_scope_consistency_client.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_r
7272
std::cout.flush();
7373
auto result1 = client1->async_send_request(request1);
7474

75-
ret1 = rclcpp::spin_until_future_complete(node, result1, 5s);
75+
ret1 = rclcpp::spin_until_complete(node, result1, 5s);
7676
if (ret1 == rclcpp::FutureReturnCode::SUCCESS) {
7777
printf("received first result\n");
7878
std::cout.flush();
@@ -108,7 +108,7 @@ TEST_F(CLASSNAME(service_client, RMW_IMPLEMENTATION), client_scope_consistency_r
108108
std::cout.flush();
109109
auto result2 = client2->async_send_request(request2);
110110

111-
auto ret2 = rclcpp::spin_until_future_complete(node, result2, 5s);
111+
auto ret2 = rclcpp::spin_until_complete(node, result2, 5s);
112112
if (ret2 == rclcpp::FutureReturnCode::SUCCESS) {
113113
printf("received second result\n");
114114
std::cout.flush();

test_rclcpp/test/test_multiple_service_calls.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -84,13 +84,13 @@ TEST_F(CLASSNAME(test_two_service_calls, RMW_IMPLEMENTATION), two_service_calls)
8484

8585
printf("Waiting for first reply...\n");
8686
fflush(stdout);
87-
rclcpp::spin_until_future_complete(node, result1);
87+
rclcpp::spin_until_complete(node, result1);
8888
printf("Received first reply\n");
8989
EXPECT_EQ(1, result1.get()->sum);
9090

9191
printf("Waiting for second reply...\n");
9292
fflush(stdout);
93-
rclcpp::spin_until_future_complete(node, result2);
93+
rclcpp::spin_until_complete(node, result2);
9494
printf("Received second reply\n");
9595
EXPECT_EQ(2, result2.get()->sum);
9696
}

test_rclcpp/test/test_multithreaded.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -223,7 +223,7 @@ TEST_F(CLASSNAME(test_multithreaded, RMW_IMPLEMENTATION), multi_consumer_clients
223223
}
224224
// Wait on each future
225225
for (uint32_t i = 0; i < results.size(); ++i) {
226-
auto result = executor.spin_until_future_complete(results[i]);
226+
auto result = executor.spin_until_complete(results[i]);
227227
ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, result);
228228
}
229229

test_rclcpp/test/test_services_client.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_noreqid) {
5959

6060
auto result = client->async_send_request(request);
6161

62-
auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result.
62+
auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result.
6363
ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
6464

6565
EXPECT_EQ(3, result.get()->sum);
@@ -79,7 +79,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_reqid) {
7979

8080
auto result = client->async_send_request(request);
8181

82-
auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result.
82+
auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result.
8383
ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
8484

8585
EXPECT_EQ(9, result.get()->sum);
@@ -106,7 +106,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_return_request)
106106
EXPECT_EQ(9, future.get().second->sum);
107107
});
108108

109-
auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result.
109+
auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result.
110110
ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
111111
}
112112

@@ -131,7 +131,7 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_de
131131
EXPECT_EQ(9, future.get().second->sum);
132132
});
133133

134-
auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result.
134+
auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result.
135135
ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
136136
}
137137

@@ -156,6 +156,6 @@ TEST_F(CLASSNAME(test_services_client, RMW_IMPLEMENTATION), test_add_two_ints_de
156156
EXPECT_EQ(9, future.get().second->sum);
157157
});
158158

159-
auto ret = rclcpp::spin_until_future_complete(node, result, 5s); // Wait for the result.
159+
auto ret = rclcpp::spin_until_complete(node, result, 5s); // Wait for the result.
160160
ASSERT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS);
161161
}

0 commit comments

Comments
 (0)