@@ -35,6 +35,7 @@ using hardware_interface::lifecycle_state_names::ACTIVE;
35
35
using hardware_interface::lifecycle_state_names::FINALIZED;
36
36
using hardware_interface::lifecycle_state_names::INACTIVE;
37
37
using hardware_interface::lifecycle_state_names::UNCONFIGURED;
38
+ using hardware_interface::lifecycle_state_names::UNKNOWN;
38
39
39
40
using ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_CLASS_TYPE;
40
41
using ros2_control_test_assets::TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES;
@@ -69,9 +70,11 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
69
70
cm_->set_parameter (
70
71
rclcpp::Parameter (" robot_description" , ros2_control_test_assets::minimal_robot_urdf));
71
72
cm_->set_parameter (rclcpp::Parameter (
72
- " activate_components_on_start" , std::vector<std::string>({TEST_ACTUATOR_HARDWARE_NAME})));
73
+ " hardware_components_initial_state.unconfigured" ,
74
+ std::vector<std::string>({TEST_SYSTEM_HARDWARE_NAME})));
73
75
cm_->set_parameter (rclcpp::Parameter (
74
- " configure_components_on_start" , std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
76
+ " hardware_components_initial_state.inactive" ,
77
+ std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
75
78
76
79
std::string robot_description = " " ;
77
80
cm_->get_parameter (" robot_description" , robot_description);
@@ -201,38 +204,6 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
201
204
}
202
205
};
203
206
204
- class TestControllerManagerHWManagementSrvsWithoutParams
205
- : public TestControllerManagerHWManagementSrvs
206
- {
207
- public:
208
- void SetUp () override
209
- {
210
- executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
211
- cm_ = std::make_shared<controller_manager::ControllerManager>(
212
- std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
213
- run_updater_ = false ;
214
-
215
- // TODO(destogl): separate this to init_tests method where parameter can be set for each test
216
- // separately
217
- cm_->set_parameter (
218
- rclcpp::Parameter (" robot_description" , ros2_control_test_assets::minimal_robot_urdf));
219
-
220
- std::string robot_description = " " ;
221
- cm_->get_parameter (" robot_description" , robot_description);
222
- if (robot_description.empty ())
223
- {
224
- throw std::runtime_error (
225
- " Unable to initialize resource manager, no robot description found." );
226
- }
227
-
228
- auto msg = std_msgs::msg::String ();
229
- msg.data = robot_description;
230
- cm_->robot_description_callback (msg);
231
-
232
- SetUpSrvsCMExecutor ();
233
- }
234
- };
235
-
236
207
TEST_F (TestControllerManagerHWManagementSrvs, list_hardware_components)
237
208
{
238
209
// Default status after start:
@@ -390,6 +361,38 @@ TEST_F(TestControllerManagerHWManagementSrvs, selective_activate_deactivate_comp
390
361
}));
391
362
}
392
363
364
+ class TestControllerManagerHWManagementSrvsWithoutParams
365
+ : public TestControllerManagerHWManagementSrvs
366
+ {
367
+ public:
368
+ void SetUp () override
369
+ {
370
+ executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
371
+ cm_ = std::make_shared<controller_manager::ControllerManager>(
372
+ std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
373
+ run_updater_ = false ;
374
+
375
+ // TODO(destogl): separate this to init_tests method where parameter can be set for each test
376
+ // separately
377
+ cm_->set_parameter (
378
+ rclcpp::Parameter (" robot_description" , ros2_control_test_assets::minimal_robot_urdf));
379
+
380
+ std::string robot_description = " " ;
381
+ cm_->get_parameter (" robot_description" , robot_description);
382
+ if (robot_description.empty ())
383
+ {
384
+ throw std::runtime_error (
385
+ " Unable to initialize resource manager, no robot description found." );
386
+ }
387
+
388
+ auto msg = std_msgs::msg::String ();
389
+ msg.data = robot_description;
390
+ cm_->robot_description_callback (msg);
391
+
392
+ SetUpSrvsCMExecutor ();
393
+ }
394
+ };
395
+
393
396
TEST_F (TestControllerManagerHWManagementSrvsWithoutParams, test_default_activation_of_all_hardware)
394
397
{
395
398
// "configure_components_on_start" and "activate_components_on_start" are not set (empty)
@@ -413,3 +416,64 @@ TEST_F(TestControllerManagerHWManagementSrvsWithoutParams, test_default_activati
413
416
{{false , false , false , false }, {false , false , false , false , false , false , false }}, // system
414
417
}));
415
418
}
419
+
420
+ // BEGIN: Deprecated parameters
421
+ class TestControllerManagerHWManagementSrvsOldParameters
422
+ : public TestControllerManagerHWManagementSrvs
423
+ {
424
+ public:
425
+ void SetUp () override
426
+ {
427
+ executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
428
+ cm_ = std::make_shared<controller_manager::ControllerManager>(
429
+ std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
430
+ run_updater_ = false ;
431
+
432
+ cm_->set_parameter (
433
+ rclcpp::Parameter (" robot_description" , ros2_control_test_assets::minimal_robot_urdf));
434
+ cm_->set_parameter (rclcpp::Parameter (
435
+ " activate_components_on_start" , std::vector<std::string>({TEST_ACTUATOR_HARDWARE_NAME})));
436
+ cm_->set_parameter (rclcpp::Parameter (
437
+ " configure_components_on_start" , std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
438
+
439
+ std::string robot_description = " " ;
440
+ cm_->get_parameter (" robot_description" , robot_description);
441
+ if (robot_description.empty ())
442
+ {
443
+ throw std::runtime_error (
444
+ " Unable to initialize resource manager, no robot description found." );
445
+ }
446
+
447
+ auto msg = std_msgs::msg::String ();
448
+ msg.data = robot_description;
449
+ cm_->robot_description_callback (msg);
450
+
451
+ SetUpSrvsCMExecutor ();
452
+ }
453
+ };
454
+
455
+ TEST_F (TestControllerManagerHWManagementSrvsOldParameters, list_hardware_components)
456
+ {
457
+ // Default status after start:
458
+ // checks if "configure_components_on_start" and "activate_components_on_start" are correctly read
459
+
460
+ list_hardware_components_and_check (
461
+ // actuator, sensor, system
462
+ std::vector<uint8_t >(
463
+ {LFC_STATE::PRIMARY_STATE_ACTIVE, LFC_STATE::PRIMARY_STATE_INACTIVE,
464
+ LFC_STATE::PRIMARY_STATE_UNCONFIGURED}),
465
+ std::vector<std::string>({ACTIVE, INACTIVE, UNCONFIGURED}),
466
+ std::vector<std::vector<std::vector<bool >>>({
467
+ // is available
468
+ {{true , true }, {true , true , true }}, // actuator
469
+ {{}, {true }}, // sensor
470
+ {{false , false , false , false }, {false , false , false , false , false , false , false }}, // system
471
+ }),
472
+ std::vector<std::vector<std::vector<bool >>>({
473
+ // is claimed
474
+ {{false , false }, {false , false , false }}, // actuator
475
+ {{}, {false }}, // sensor
476
+ {{false , false , false , false }, {false , false , false , false , false , false , false }}, // system
477
+ }));
478
+ }
479
+ // END: Deprecated parameters
0 commit comments