@@ -106,7 +106,7 @@ void test_set_parameters_async(
106
106
printf (" Setting parameters\n " );
107
107
std::vector<rclcpp::Parameter> parameters = get_test_parameters ();
108
108
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.
110
110
printf (" Got set_parameters result\n " );
111
111
112
112
if (successful_up_to < 0 || successful_up_to > static_cast <int >(parameters.size ())) {
@@ -271,7 +271,7 @@ void test_get_parameters_async(
271
271
// Test recursive depth (=0)
272
272
auto result = parameters_client->list_parameters (
273
273
{" foo" , " bar" }, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
274
- rclcpp::spin_until_future_complete (node, result);
274
+ rclcpp::spin_until_complete (node, result);
275
275
auto parameters_and_prefixes = result.get ();
276
276
for (auto & name : parameters_and_prefixes.names ) {
277
277
EXPECT_TRUE (name == " foo" || name == " bar" || name == " foo.first" || name == " foo.second" );
@@ -283,7 +283,7 @@ void test_get_parameters_async(
283
283
printf (" Listing parameters with depth 1\n " );
284
284
// Test different depth
285
285
auto result4 = parameters_client->list_parameters ({" foo" }, 1 );
286
- rclcpp::spin_until_future_complete (node, result4);
286
+ rclcpp::spin_until_complete (node, result4);
287
287
auto parameters_and_prefixes4 = result4.get ();
288
288
for (auto & name : parameters_and_prefixes4.names ) {
289
289
EXPECT_EQ (name, " foo" );
@@ -295,7 +295,7 @@ void test_get_parameters_async(
295
295
// Test different depth
296
296
printf (" Listing parameters with depth 2\n " );
297
297
auto result4a = parameters_client->list_parameters ({" foo" }, 2 );
298
- rclcpp::spin_until_future_complete (node, result4a);
298
+ rclcpp::spin_until_complete (node, result4a);
299
299
auto parameters_and_prefixes4a = result4a.get ();
300
300
for (auto & name : parameters_and_prefixes4a.names ) {
301
301
EXPECT_TRUE (name == " foo" || name == " foo.first" || name == " foo.second" );
@@ -308,7 +308,7 @@ void test_get_parameters_async(
308
308
printf (" Getting parameters\n " );
309
309
// Get a few of the parameters just set.
310
310
auto result2 = parameters_client->get_parameters ({" foo" , " bar" , " baz" });
311
- rclcpp::spin_until_future_complete (node, result2);
311
+ rclcpp::spin_until_complete (node, result2);
312
312
for (auto & parameter : result2.get ()) {
313
313
if (parameter.get_name () == " foo" ) {
314
314
EXPECT_STREQ (" foo" , parameter.get_name ().c_str ());
@@ -333,7 +333,7 @@ void test_get_parameters_async(
333
333
// Get a few non existant parameters
334
334
{
335
335
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);
337
337
std::vector<rclcpp::Parameter> retrieved_params = result3.get ();
338
338
if (allowed_undeclared == false ) {
339
339
ASSERT_EQ (0u , retrieved_params.size ());
@@ -350,7 +350,7 @@ void test_get_parameters_async(
350
350
// List all of the parameters, using an empty prefix list
351
351
auto result5 = parameters_client->list_parameters (
352
352
{}, rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
353
- rclcpp::spin_until_future_complete (node, result5);
353
+ rclcpp::spin_until_complete (node, result5);
354
354
parameters_and_prefixes = result5.get ();
355
355
std::vector<std::string> all_names = {
356
356
" foo" , " bar" , " barstr" , " baz" , " foo.first" , " foo.second" , " foobar" , " use_sim_time"
0 commit comments