Skip to content

Commit 882b489

Browse files
authored
Handle SIGINT properly in the controller manager (#2014)
1 parent f4e3f5a commit 882b489

File tree

4 files changed

+95
-2
lines changed

4 files changed

+95
-2
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,13 @@ class ControllerManager : public rclcpp::Node
8080
const std::string & node_namespace = "",
8181
const rclcpp::NodeOptions & options = get_cm_node_options());
8282

83-
virtual ~ControllerManager() = default;
83+
virtual ~ControllerManager();
84+
85+
/// Shutdown all controllers in the controller manager.
86+
/**
87+
* \return true if all controllers are successfully shutdown, false otherwise.
88+
*/
89+
bool shutdown_controllers();
8490

8591
void robot_description_callback(const std_msgs::msg::String & msg);
8692

@@ -531,6 +537,7 @@ class ControllerManager : public rclcpp::Node
531537
int used_by_realtime_controllers_index_ = -1;
532538
};
533539

540+
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{nullptr};
534541
RTControllerListWrapper rt_controllers_wrapper_;
535542
std::unordered_map<std::string, ControllerChainSpec> controller_chain_spec_;
536543
std::vector<std::string> ordered_controllers_names_;

controller_manager/src/controller_manager.cpp

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -291,6 +291,46 @@ ControllerManager::ControllerManager(
291291
init_controller_manager();
292292
}
293293

294+
ControllerManager::~ControllerManager()
295+
{
296+
if (preshutdown_cb_handle_)
297+
{
298+
rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context();
299+
context->remove_pre_shutdown_callback(*(preshutdown_cb_handle_.get()));
300+
preshutdown_cb_handle_.reset();
301+
}
302+
}
303+
304+
bool ControllerManager::shutdown_controllers()
305+
{
306+
RCLCPP_INFO(get_logger(), "Shutting down all controllers in the controller manager.");
307+
// Shutdown all controllers
308+
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
309+
std::vector<ControllerSpec> controllers_list = rt_controllers_wrapper_.get_updated_list(guard);
310+
bool ctrls_shutdown_status = true;
311+
for (auto & controller : controllers_list)
312+
{
313+
if (is_controller_active(controller.c))
314+
{
315+
RCLCPP_INFO(
316+
get_logger(), "Deactivating controller '%s'", controller.c->get_node()->get_name());
317+
controller.c->get_node()->deactivate();
318+
controller.c->release_interfaces();
319+
}
320+
if (is_controller_inactive(*controller.c) || is_controller_unconfigured(*controller.c))
321+
{
322+
RCLCPP_INFO(
323+
get_logger(), "Shutting down controller '%s'", controller.c->get_node()->get_name());
324+
shutdown_controller(controller);
325+
}
326+
ctrls_shutdown_status &=
327+
(controller.c->get_node()->get_current_state().id() ==
328+
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
329+
executor_->remove_node(controller.c->get_node()->get_node_base_interface());
330+
}
331+
return ctrls_shutdown_status;
332+
}
333+
294334
void ControllerManager::init_controller_manager()
295335
{
296336
// Get parameters needed for RT "update" loop to work
@@ -329,6 +369,29 @@ void ControllerManager::init_controller_manager()
329369
diagnostics_updater_.add(
330370
"Controller Manager Activity", this,
331371
&ControllerManager::controller_manager_diagnostic_callback);
372+
373+
// Add on_shutdown callback to stop the controller manager
374+
rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context();
375+
preshutdown_cb_handle_ =
376+
std::make_unique<rclcpp::PreShutdownCallbackHandle>(context->add_pre_shutdown_callback(
377+
[this]()
378+
{
379+
RCLCPP_INFO(get_logger(), "Shutdown request received....");
380+
if (this->get_node_base_interface()->get_associated_with_executor_atomic().load())
381+
{
382+
executor_->remove_node(this->get_node_base_interface());
383+
}
384+
executor_->cancel();
385+
if (!this->shutdown_controllers())
386+
{
387+
RCLCPP_ERROR(get_logger(), "Failed shutting down the controllers.");
388+
}
389+
if (!resource_manager_->shutdown_components())
390+
{
391+
RCLCPP_ERROR(get_logger(), "Failed shutting down hardware components.");
392+
}
393+
RCLCPP_INFO(get_logger(), "Shutting down the controller manager.");
394+
}));
332395
}
333396

334397
void ControllerManager::initialize_parameters()

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,13 @@ class ResourceManager
7676

7777
virtual ~ResourceManager();
7878

79+
/// Shutdown all hardware components, irrespective of their state.
80+
/**
81+
* The method is called when the controller manager is being shutdown.
82+
* @return true if all hardware components are successfully shutdown, false otherwise.
83+
*/
84+
bool shutdown_components();
85+
7986
/// Load resources from on a given URDF.
8087
/**
8188
* The resource manager can be post-initialized with a given URDF.

hardware_interface/src/resource_manager.cpp

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -573,7 +573,7 @@ class ResourceStorage
573573
result = shutdown_hardware(hardware);
574574
break;
575575
case State::PRIMARY_STATE_ACTIVE:
576-
result = shutdown_hardware(hardware);
576+
result = deactivate_hardware(hardware) && shutdown_hardware(hardware);
577577
break;
578578
case State::PRIMARY_STATE_FINALIZED:
579579
result = true;
@@ -1040,6 +1040,22 @@ ResourceManager::ResourceManager(
10401040
}
10411041
}
10421042

1043+
bool ResourceManager::shutdown_components()
1044+
{
1045+
std::unique_lock<std::recursive_mutex> guard(resource_interfaces_lock_);
1046+
bool shutdown_status = true;
1047+
for (auto const & hw_info : resource_storage_->hardware_info_map_)
1048+
{
1049+
rclcpp_lifecycle::State finalized_state(
1050+
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED);
1051+
if (set_component_state(hw_info.first, finalized_state) != return_type::OK)
1052+
{
1053+
shutdown_status = false;
1054+
}
1055+
}
1056+
return shutdown_status;
1057+
}
1058+
10431059
// CM API: Called in "callback/slow"-thread
10441060
bool ResourceManager::load_and_initialize_components(
10451061
const std::string & urdf, const unsigned int update_rate)

0 commit comments

Comments
 (0)