@@ -541,34 +541,38 @@ bool ControllerManager::shutdown_controllers()
541541
542542void ControllerManager::init_controller_manager ()
543543{
544- controller_manager_activity_publisher_ =
545- create_publisher<controller_manager_msgs::msg::ControllerManagerActivity>(
546- " ~/activity" , rclcpp::QoS (1 ).reliable ().transient_local ());
547- rt_controllers_wrapper_.set_on_switch_callback (
548- std::bind (&ControllerManager::publish_activity, this ));
549- resource_manager_->set_on_component_state_switch_callback (
550- std::bind (&ControllerManager::publish_activity, this ));
544+ if (!resource_manager_ && !robot_description_.empty ())
545+ {
546+ init_resource_manager (robot_description_);
547+ }
551548
552- // Get parameters needed for RT "update" loop to work
553- if (is_resource_manager_initialized ())
549+ if (!is_resource_manager_initialized ())
554550 {
555- if (params_->enforce_command_limits )
551+ // fallback state
552+ init_min_resource_manager ();
553+ if (!robot_description_notification_timer_)
556554 {
557- resource_manager_->import_joint_limiters (robot_description_);
555+ robot_description_notification_timer_ = create_wall_timer (
556+ std::chrono::seconds (1 ),
557+ [&]()
558+ {
559+ RCLCPP_WARN (get_logger (), " Waiting for data on 'robot_description' topic to finish initialization" );
560+ });
558561 }
559- init_services ();
560- }
561- else
562+ }else
562563 {
563- robot_description_notification_timer_ = create_wall_timer (
564- std::chrono::seconds (1 ),
565- [&]()
566- {
567- RCLCPP_WARN (
568- get_logger (), " Waiting for data on 'robot_description' topic to finish initialization" );
569- });
564+ RCLCPP_INFO (get_logger (),
565+ " Resource Manager has been successfully initialized. Starting Controller Manager "
566+ " services..." );
567+ init_services ();
570568 }
571569
570+ controller_manager_activity_publisher_ =
571+ create_publisher<controller_manager_msgs::msg::ControllerManagerActivity>(
572+ " ~/activity" , rclcpp::QoS (1 ).reliable ().transient_local ());
573+ rt_controllers_wrapper_.set_on_switch_callback (
574+ std::bind (&ControllerManager::publish_activity, this ));
575+
572576 // set QoS to transient local to get messages that have already been published
573577 // (if robot state publisher starts before controller manager)
574578 robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
@@ -674,9 +678,15 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
674678 get_logger (),
675679 " ResourceManager has already loaded a urdf. Ignoring attempt to reload a robot description." );
676680 return ;
677- }
681+ }
682+
678683 init_resource_manager (robot_description_);
679- if (is_resource_manager_initialized ())
684+ if (!is_resource_manager_initialized ())
685+ {
686+ // The RM failed to init AFTER we received the description - a critical error.
687+ // don't finalize controller manager, instead keep waiting for robot description - fallback state
688+ init_min_resource_manager ();
689+ } else
680690 {
681691 RCLCPP_INFO (
682692 get_logger (),
@@ -688,26 +698,51 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
688698
689699void ControllerManager::init_resource_manager (const std::string & robot_description)
690700{
691- if (params_->enforce_command_limits )
692- {
693- resource_manager_->import_joint_limiters (robot_description_);
694- }
695701 hardware_interface::ResourceManagerParams params;
696702 params.robot_description = robot_description;
697703 params.clock = trigger_clock_;
698704 params.logger = this ->get_logger ();
699705 params.executor = executor_;
700706 params.node_namespace = this ->get_namespace ();
701707 params.update_rate = static_cast <unsigned int >(params_->update_rate );
702- if (!resource_manager_->load_and_initialize_components (params))
708+ resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(params, false );
709+
710+ RCLCPP_INFO_EXPRESSION (
711+ get_logger (), params_->enforce_command_limits , " Enforcing command limits is enabled..." );
712+ if (params_->enforce_command_limits )
703713 {
704- RCLCPP_WARN (
714+ try
715+ {
716+ resource_manager_->import_joint_limiters (robot_description);
717+ }
718+ catch (const std::exception & e)
719+ {
720+ RCLCPP_ERROR (get_logger (), " Error importing joint limiters: %s" , e.what ());
721+ return ;
722+ }
723+ }
724+
725+ try
726+ {
727+ if (!resource_manager_->load_and_initialize_components (params))
728+ {
729+ RCLCPP_WARN (
730+ get_logger (),
731+ " Could not load and initialize hardware. Please check previous output for more details. "
732+ " After you have corrected your URDF, try to publish robot description again." );
733+ return ;
734+ }
735+ }
736+ catch (const std::exception &e)
737+ {
738+ // Other possible errors when loading components
739+ RCLCPP_ERROR (
705740 get_logger (),
706- " Could not load and initialize hardware. Please check previous output for more details. "
707- " After you have corrected your URDF, try to publish robot description again." );
741+ " Exception caught while loading and initializing components: %s" , e.what ());
708742 return ;
709743 }
710-
744+ resource_manager_->set_on_component_state_switch_callback (std::bind (&ControllerManager::publish_activity, this ));
745+
711746 // Get all components and if they are not defined in parameters activate them automatically
712747 auto components_to_activate = resource_manager_->get_components_status ();
713748
@@ -855,6 +890,13 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
855890 }
856891}
857892
893+ void ControllerManager::init_min_resource_manager ()
894+ {
895+ resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(trigger_clock_, get_logger ());
896+ resource_manager_->set_on_component_state_switch_callback (
897+ std::bind (&ControllerManager::publish_activity, this ));
898+ }
899+
858900void ControllerManager::init_services ()
859901{
860902 // TODO(anyone): Due to issues with the MutliThreadedExecutor, this control loop does not rely on
0 commit comments