@@ -127,7 +127,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
127
127
<< " Update should not reach an unconfigured controller" ;
128
128
129
129
EXPECT_EQ (
130
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
130
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
131
+ test_controller->get_lifecycle_state ().id ());
131
132
132
133
// configure controller
133
134
{
@@ -141,7 +142,9 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
141
142
EXPECT_EQ (0u , test_controller->internal_counter ) << " Controller is not started" ;
142
143
EXPECT_EQ (0u , test_controller2->internal_counter ) << " Controller is not started" ;
143
144
144
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
145
+ EXPECT_EQ (
146
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
147
+ test_controller->get_lifecycle_state ().id ());
145
148
146
149
// Start controller, will take effect at the end of the update function
147
150
std::vector<std::string> start_controllers = {" fake_controller" , TEST_CONTROLLER2_NAME};
@@ -182,7 +185,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
182
185
ControllerManagerRunner cm_runner (this );
183
186
EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
184
187
}
185
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state ().id ());
188
+ EXPECT_EQ (
189
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
186
190
187
191
EXPECT_EQ (
188
192
controller_interface::return_type::OK,
@@ -210,7 +214,9 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
210
214
EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
211
215
}
212
216
213
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
217
+ EXPECT_EQ (
218
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
219
+ test_controller->get_lifecycle_state ().id ());
214
220
auto unload_future = std::async (
215
221
std::launch::async, &controller_manager::ControllerManager::unload_controller, cm_,
216
222
test_controller::TEST_CONTROLLER_NAME);
@@ -221,7 +227,8 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
221
227
EXPECT_EQ (controller_interface::return_type::OK, unload_future.get ());
222
228
223
229
EXPECT_EQ (
224
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
230
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
231
+ test_controller->get_lifecycle_state ().id ());
225
232
EXPECT_EQ (1 , test_controller.use_count ());
226
233
}
227
234
@@ -242,7 +249,8 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
242
249
<< " Update should not reach an unconfigured controller" ;
243
250
244
251
EXPECT_EQ (
245
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
252
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
253
+ test_controller->get_lifecycle_state ().id ());
246
254
247
255
test_controller->get_node ()->set_parameter ({" update_rate" , 4 });
248
256
// configure controller
@@ -255,7 +263,9 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
255
263
cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
256
264
EXPECT_EQ (0u , test_controller->internal_counter ) << " Controller is not started" ;
257
265
258
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
266
+ EXPECT_EQ (
267
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
268
+ test_controller->get_lifecycle_state ().id ());
259
269
260
270
// Start controller, will take effect at the end of the update function
261
271
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
@@ -276,7 +286,8 @@ TEST_P(TestControllerManagerWithStrictness, per_controller_update_rate)
276
286
EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
277
287
}
278
288
279
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state ().id ());
289
+ EXPECT_EQ (
290
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
280
291
281
292
// As the controller frequency is 4Hz, it needs to pass 25 iterations for 1 update cycle
282
293
for (size_t i = 0 ; i < 25 ; i++)
@@ -323,7 +334,8 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
323
334
<< " Update should not reach an unconfigured controller" ;
324
335
325
336
EXPECT_EQ (
326
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
337
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
338
+ test_controller->get_lifecycle_state ().id ());
327
339
328
340
rclcpp::Parameter update_rate_parameter (" update_rate" , static_cast <int >(ctrl_update_rate));
329
341
test_controller->get_node ()->set_parameter (update_rate_parameter);
@@ -337,7 +349,9 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
337
349
cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
338
350
EXPECT_EQ (last_internal_counter, test_controller->internal_counter )
339
351
<< " Controller is not started" ;
340
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
352
+ EXPECT_EQ (
353
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
354
+ test_controller->get_lifecycle_state ().id ());
341
355
342
356
// Start controller, will take effect at the end of the update function
343
357
std::vector<std::string> start_controllers = {test_controller::TEST_CONTROLLER_NAME};
@@ -360,7 +374,8 @@ TEST_P(TestControllerManagerWithUpdateRates, per_controller_equal_and_higher_upd
360
374
EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
361
375
}
362
376
363
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state ().id ());
377
+ EXPECT_EQ (
378
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
364
379
365
380
const auto pre_internal_counter = test_controller->internal_counter ;
366
381
rclcpp::Rate loop_rate (cm_->get_update_rate ());
@@ -430,7 +445,8 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
430
445
EXPECT_EQ (2 , test_controller.use_count ());
431
446
432
447
EXPECT_EQ (
433
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
448
+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
449
+ test_controller->get_lifecycle_state ().id ());
434
450
435
451
test_controller->get_node ()->set_parameter ({" update_rate" , static_cast <int >(ctrl_update_rate)});
436
452
// configure controller
@@ -443,7 +459,9 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
443
459
cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
444
460
EXPECT_EQ (0u , test_controller->internal_counter ) << " Controller is not started" ;
445
461
446
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
462
+ EXPECT_EQ (
463
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
464
+ test_controller->get_lifecycle_state ().id ());
447
465
448
466
// Start controller, will take effect at the end of the update function
449
467
time_ = test_controller->get_node ()->now (); // set to something nonzero
@@ -467,7 +485,8 @@ TEST_P(TestControllerUpdateRates, check_the_controller_update_rate)
467
485
EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
468
486
}
469
487
470
- EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_state ().id ());
488
+ EXPECT_EQ (
489
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
471
490
472
491
EXPECT_EQ (test_controller->get_update_rate (), ctrl_update_rate);
473
492
const auto cm_update_rate = cm_->get_update_rate ();
0 commit comments