@@ -504,6 +504,10 @@ void ControllerManager::init_services()
504504 " ~/unload_controller" ,
505505 std::bind (&ControllerManager::unload_controller_service_cb, this , _1, _2), qos_services,
506506 best_effort_callback_group_);
507+ cleanup_controller_service_ = create_service<controller_manager_msgs::srv::CleanupController>(
508+ " ~/cleanup_controller" ,
509+ std::bind (&ControllerManager::cleanup_controller_service_cb, this , _1, _2), qos_services,
510+ best_effort_callback_group_);
507511 list_hardware_components_service_ =
508512 create_service<controller_manager_msgs::srv::ListHardwareComponents>(
509513 " ~/list_hardware_components" ,
@@ -664,6 +668,61 @@ controller_interface::return_type ControllerManager::unload_controller(
664668 return controller_interface::return_type::OK;
665669}
666670
671+ controller_interface::return_type ControllerManager::cleanup_controller (
672+ const std::string & controller_name)
673+ {
674+ std::lock_guard<std::recursive_mutex> guard (rt_controllers_wrapper_.controllers_lock_ );
675+ std::vector<ControllerSpec> & to = rt_controllers_wrapper_.get_unused_list (guard);
676+ const std::vector<ControllerSpec> & from = rt_controllers_wrapper_.get_updated_list (guard);
677+
678+ // Transfers the active controllers over, skipping the one to be removed and the active ones.
679+ to = from;
680+
681+ auto found_it = std::find_if (
682+ to.begin (), to.end (),
683+ std::bind (controller_name_compare, std::placeholders::_1, controller_name));
684+ if (found_it == to.end ())
685+ {
686+ // Fails if we could not remove the controllers
687+ to.clear ();
688+ RCLCPP_ERROR (
689+ get_logger (),
690+ " Could not clear controller with name '%s' because no controller with this name exists" ,
691+ controller_name.c_str ());
692+ return controller_interface::return_type::ERROR;
693+ }
694+
695+ auto & controller = *found_it;
696+
697+ if (is_controller_active (*controller.c ))
698+ {
699+ to.clear ();
700+ RCLCPP_ERROR (
701+ get_logger (), " Could not clear controller with name '%s' because it is still active" ,
702+ controller_name.c_str ());
703+ return controller_interface::return_type::ERROR;
704+ }
705+
706+ RCLCPP_DEBUG (get_logger (), " Cleanup controller" );
707+ // TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
708+ // cleaning-up controllers?
709+ controller.c ->get_node ()->cleanup ();
710+ executor_->remove_node (controller.c ->get_node ()->get_node_base_interface ());
711+ to.erase (found_it);
712+
713+ // Destroys the old controllers list when the realtime thread is finished with it.
714+ RCLCPP_DEBUG (get_logger (), " Realtime switches over to new controller list" );
715+ rt_controllers_wrapper_.switch_updated_list (guard);
716+ std::vector<ControllerSpec> & new_unused_list = rt_controllers_wrapper_.get_unused_list (guard);
717+ RCLCPP_DEBUG (get_logger (), " Destruct controller" );
718+ new_unused_list.clear ();
719+ RCLCPP_DEBUG (get_logger (), " Destruct controller finished" );
720+
721+ RCLCPP_DEBUG (get_logger (), " Successfully cleaned controller '%s'" , controller_name.c_str ());
722+
723+ return controller_interface::return_type::OK;
724+ }
725+
667726std::vector<ControllerSpec> ControllerManager::get_loaded_controllers () const
668727{
669728 std::lock_guard<std::recursive_mutex> guard (rt_controllers_wrapper_.controllers_lock_ );
@@ -1878,6 +1937,22 @@ void ControllerManager::unload_controller_service_cb(
18781937 get_logger (), " unloading service finished for controller '%s' " , request->name .c_str ());
18791938}
18801939
1940+ void ControllerManager::cleanup_controller_service_cb (
1941+ const std::shared_ptr<controller_manager_msgs::srv::CleanupController::Request> request,
1942+ std::shared_ptr<controller_manager_msgs::srv::CleanupController::Response> response)
1943+ {
1944+ // lock services
1945+ RCLCPP_DEBUG (
1946+ get_logger (), " cleanup service called for controller '%s' " , request->name .c_str ());
1947+ std::lock_guard<std::mutex> guard (services_lock_);
1948+ RCLCPP_DEBUG (get_logger (), " cleanup service locked" );
1949+
1950+ response->ok = cleanup_controller (request->name ) == controller_interface::return_type::OK;
1951+
1952+ RCLCPP_DEBUG (
1953+ get_logger (), " cleanup service finished for controller '%s' " , request->name .c_str ());
1954+ }
1955+
18811956void ControllerManager::list_hardware_components_srv_cb (
18821957 const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request>,
18831958 std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response)
0 commit comments