Skip to content

Commit 472b1d5

Browse files
committed
Add error recovery for invalid URDFs in controller manager initialization, robot description callback and resource manager constructor
1 parent efa1dec commit 472b1d5

File tree

3 files changed

+106
-36
lines changed

3 files changed

+106
-36
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

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

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

97+
void init_min_resource_manager();
98+
9799
controller_interface::ControllerInterfaceBaseSharedPtr load_controller(
98100
const std::string & controller_name, const std::string & controller_type);
99101

@@ -242,6 +244,17 @@ class ControllerManager : public rclcpp::Node
242244
*/
243245
rclcpp::Clock::SharedPtr get_trigger_clock() const;
244246

247+
/**
248+
* @brief Return the robot description timer.
249+
*
250+
* It can be used to determine whether the Controller Manager
251+
* is currently waiting for a robot description to be published.
252+
*
253+
* @return rclcpp::TimerBase::SharedPtr if the timer exists, nullptr otherwise
254+
*/
255+
rclcpp::TimerBase::SharedPtr get_robot_description_timer() const {
256+
return robot_description_notification_timer_;
257+
}
245258
protected:
246259
void init_services();
247260

controller_manager/src/controller_manager.cpp

Lines changed: 74 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -541,34 +541,38 @@ bool ControllerManager::shutdown_controllers()
541541

542542
void 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

689699
void 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+
858900
void ControllerManager::init_services()
859901
{
860902
// TODO(anyone): Due to issues with the MutliThreadedExecutor, this control loop does not rely on

hardware_interface/src/resource_manager.cpp

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1420,9 +1420,17 @@ ResourceManager::ResourceManager(
14201420
params.allow_controller_activation_with_inactive_hardware;
14211421
return_failed_hardware_names_on_return_deactivate_write_cycle_ =
14221422
params.return_failed_hardware_names_on_return_deactivate_write_cycle_;
1423-
if (load)
1423+
1424+
try
14241425
{
1425-
load_and_initialize_components(params);
1426+
if (load && !load_and_initialize_components(params))
1427+
{
1428+
RCLCPP_WARN(
1429+
get_logger(),
1430+
"Could not load and initialize hardware. Please check previous output for more details. "
1431+
"After you have corrected your URDF, try to publish robot description again.");
1432+
return;
1433+
}
14261434
if (params.activate_all)
14271435
{
14281436
for (auto const & hw_info : resource_storage_->hardware_info_map_)
@@ -1433,6 +1441,14 @@ ResourceManager::ResourceManager(
14331441
}
14341442
}
14351443
}
1444+
catch (const std::exception &e)
1445+
{
1446+
// Other possible errors when loading components
1447+
RCLCPP_ERROR(
1448+
get_logger(),
1449+
"Exception caught while loading and initializing components: %s", e.what());
1450+
return;
1451+
}
14361452
}
14371453

14381454
bool ResourceManager::shutdown_components()
@@ -1455,8 +1471,6 @@ bool ResourceManager::shutdown_components()
14551471
bool ResourceManager::load_and_initialize_components(
14561472
const hardware_interface::ResourceManagerParams & params)
14571473
{
1458-
components_are_loaded_and_initialized_ = true;
1459-
14601474
resource_storage_->robot_description_ = params.robot_description;
14611475
resource_storage_->cm_update_rate_ = params.update_rate;
14621476

@@ -1473,6 +1487,7 @@ bool ResourceManager::load_and_initialize_components(
14731487
const std::string sensor_type = "sensor";
14741488
const std::string actuator_type = "actuator";
14751489

1490+
components_are_loaded_and_initialized_ = true;
14761491
std::lock_guard<std::recursive_mutex> resource_guard(resources_lock_);
14771492
std::lock_guard<std::recursive_mutex> limiters_guard(joint_limiters_lock_);
14781493
for (const auto & individual_hardware_info : hardware_info)

0 commit comments

Comments
 (0)