Skip to content

Commit c34126d

Browse files
author
nibanovic
committed
use intantiation instead of init_min_resource_manager()
1 parent 8f976b8 commit c34126d

File tree

2 files changed

+2
-10
lines changed

2 files changed

+2
-10
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -94,8 +94,6 @@ class ControllerManager : public rclcpp::Node
9494

9595
void init_resource_manager(const std::string & robot_description);
9696

97-
void init_min_resource_manager();
98-
9997
controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
10098
const std::string & controller_name, const std::string & controller_type);
10199

controller_manager/src/controller_manager.cpp

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -502,7 +502,7 @@ void ControllerManager::init_controller_manager()
502502
if (!is_resource_manager_initialized())
503503
{
504504
// fallback state
505-
init_min_resource_manager();
505+
resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(trigger_clock_, get_logger());
506506
if (!robot_description_notification_timer_)
507507
{
508508
robot_description_notification_timer_ = create_wall_timer(
@@ -638,7 +638,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
638638
{
639639
// The RM failed to init AFTER we received the description - a critical error.
640640
// don't finalize controller manager, instead keep waiting for robot description - fallback state
641-
init_min_resource_manager();
641+
resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(trigger_clock_, get_logger());
642642
} else
643643
{
644644
RCLCPP_INFO(
@@ -842,12 +842,6 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
842842
}
843843
}
844844

845-
void ControllerManager::init_min_resource_manager()
846-
{
847-
resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(trigger_clock_, get_logger());
848-
resource_manager_->set_on_component_state_switch_callback(
849-
std::bind(&ControllerManager::publish_activity, this));
850-
}
851845

852846
void ControllerManager::init_services()
853847
{

0 commit comments

Comments
 (0)