@@ -383,51 +383,47 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
383383 using lifecycle_msgs::msg::State;
384384
385385 auto set_components_to_state =
386- [&](const std::string & parameter_name , rclcpp_lifecycle::State state)
386+ [&](const std::vector<std:: string> & components_to_set , rclcpp_lifecycle::State state)
387387 {
388- std::vector<std::string> components_to_set = std::vector<std::string>({});
389- if (get_parameter (parameter_name, components_to_set))
388+ for (const auto & component : components_to_set)
390389 {
391- for ( const auto & component : components_to_set )
390+ if ( component. empty () )
392391 {
393- if (component.empty ())
394- {
395- continue ;
396- }
397- if (components_to_activate.find (component) == components_to_activate.end ())
398- {
399- RCLCPP_WARN (
400- get_logger (), " Hardware component '%s' is unknown, therefore not set in '%s' state." ,
401- component.c_str (), state.label ().c_str ());
402- }
403- else
392+ continue ;
393+ }
394+ if (components_to_activate.find (component) == components_to_activate.end ())
395+ {
396+ RCLCPP_WARN (
397+ get_logger (), " Hardware component '%s' is unknown, therefore not set in '%s' state." ,
398+ component.c_str (), state.label ().c_str ());
399+ }
400+ else
401+ {
402+ RCLCPP_INFO (
403+ get_logger (), " Setting component '%s' to '%s' state." , component.c_str (),
404+ state.label ().c_str ());
405+ if (
406+ resource_manager_->set_component_state (component, state) ==
407+ hardware_interface::return_type::ERROR)
404408 {
405- RCLCPP_INFO (
406- get_logger (), " Setting component '%s' to '%s' state." , component.c_str (),
407- state.label ().c_str ());
408- if (
409- resource_manager_->set_component_state (component, state) ==
410- hardware_interface::return_type::ERROR)
411- {
412- throw std::runtime_error (
413- " Failed to set the initial state of the component : " + component + " to " +
414- state.label ());
415- }
416- components_to_activate.erase (component);
409+ throw std::runtime_error (
410+ " Failed to set the initial state of the component : " + component + " to " +
411+ state.label ());
417412 }
413+ components_to_activate.erase (component);
418414 }
419415 }
420416 };
421417
422418 // unconfigured (loaded only)
423419 set_components_to_state (
424- " hardware_components_initial_state.unconfigured" ,
420+ params_-> hardware_components_initial_state .unconfigured ,
425421 rclcpp_lifecycle::State (
426422 State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED));
427423
428424 // inactive (configured)
429425 set_components_to_state (
430- " hardware_components_initial_state.inactive" ,
426+ params_-> hardware_components_initial_state .inactive ,
431427 rclcpp_lifecycle::State (
432428 State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE));
433429
0 commit comments