@@ -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+
294334void 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
334397void ControllerManager::initialize_parameters ()
0 commit comments