Skip to content

Issue 759: This will add the cleanup service #1236

New issue

Have a question about this project? # for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “#”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? # to your account

Open
wants to merge 12 commits into
base: master
Choose a base branch
from
11 changes: 11 additions & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,17 @@ if(BUILD_TESTING)
ros2_control_test_assets::ros2_control_test_assets
)

ament_add_gmock(test_cleanup_controller
test/test_cleanup_controller.cpp
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$<CONFIG>
)
target_link_libraries(test_cleanup_controller
controller_manager
test_controller
test_controller_failed_init
ros2_control_test_assets::ros2_control_test_assets
)

ament_add_gmock(test_controllers_chaining_with_controller_manager
test/test_controllers_chaining_with_controller_manager.cpp
)
Expand Down
2 changes: 2 additions & 0 deletions controller_manager/controller_manager/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
set_hardware_component_state,
switch_controllers,
unload_controller,
cleanup_controller,
)

__all__ = [
Expand All @@ -36,4 +37,5 @@
"set_hardware_component_state",
"switch_controllers",
"unload_controller",
"cleanup_controller",
]
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
SetHardwareComponentState,
SwitchController,
UnloadController,
CleanupController,
)

import rclpy
Expand Down Expand Up @@ -175,3 +176,11 @@ def unload_controller(node, controller_manager_name, controller_name, service_ti
request,
service_timeout,
)


def cleanup_controller(node, controller_manager_name, controller_name):
request = CleanupController.Request()
request.name = controller_name
return service_caller(
node, f"{controller_manager_name}/cleanup_controller", CleanupController, request
)
1 change: 1 addition & 0 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,7 @@ def wait_for_controller_manager(node, controller_manager, timeout_duration):
f"{controller_manager}/reload_controller_libraries",
f"{controller_manager}/switch_controller",
f"{controller_manager}/unload_controller",
f"{controller_manager}/cleanup_controller",
)

# Wait for controller_manager
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#include "controller_manager/controller_spec.hpp"
#include "controller_manager/visibility_control.h"
#include "controller_manager_msgs/srv/cleanup_controller.hpp"
#include "controller_manager_msgs/srv/configure_controller.hpp"
#include "controller_manager_msgs/srv/list_controller_types.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
Expand Down Expand Up @@ -107,6 +108,9 @@ class ControllerManager : public rclcpp::Node
CONTROLLER_MANAGER_PUBLIC
controller_interface::return_type unload_controller(const std::string & controller_name);

CONTROLLER_MANAGER_PUBLIC
controller_interface::return_type cleanup_controller(const std::string & controller_name);

CONTROLLER_MANAGER_PUBLIC
std::vector<ControllerSpec> get_loaded_controllers() const;

Expand Down Expand Up @@ -296,6 +300,11 @@ class ControllerManager : public rclcpp::Node
const std::shared_ptr<controller_manager_msgs::srv::UnloadController::Request> request,
std::shared_ptr<controller_manager_msgs::srv::UnloadController::Response> response);

CONTROLLER_MANAGER_PUBLIC
void cleanup_controller_service_cb(
const std::shared_ptr<controller_manager_msgs::srv::CleanupController::Request> request,
std::shared_ptr<controller_manager_msgs::srv::CleanupController::Response> response);

CONTROLLER_MANAGER_PUBLIC
void list_controller_types_srv_cb(
const std::shared_ptr<controller_manager_msgs::srv::ListControllerTypes::Request> request,
Expand Down Expand Up @@ -531,6 +540,8 @@ class ControllerManager : public rclcpp::Node
switch_controller_service_;
rclcpp::Service<controller_manager_msgs::srv::UnloadController>::SharedPtr
unload_controller_service_;
rclcpp::Service<controller_manager_msgs::srv::CleanupController>::SharedPtr
cleanup_controller_service_;

rclcpp::Service<controller_manager_msgs::srv::ListHardwareComponents>::SharedPtr
list_hardware_components_service_;
Expand Down
140 changes: 108 additions & 32 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,18 @@ static const rmw_qos_profile_t qos_services = {
false};
#endif

inline bool is_controller_unconfigured(
const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED;
}

inline bool is_controller_unconfigured(
const controller_interface::ControllerInterfaceBaseSharedPtr & controller)
{
return is_controller_unconfigured(*controller);
}

inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
Expand Down Expand Up @@ -479,6 +491,10 @@ void ControllerManager::init_services()
"~/unload_controller",
std::bind(&ControllerManager::unload_controller_service_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
cleanup_controller_service_ = create_service<controller_manager_msgs::srv::CleanupController>(
"~/cleanup_controller",
std::bind(&ControllerManager::cleanup_controller_service_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
list_hardware_components_service_ =
create_service<controller_manager_msgs::srv::ListHardwareComponents>(
"~/list_hardware_components",
Expand Down Expand Up @@ -594,65 +610,110 @@ controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_c
return load_controller(controller_name, controller_type);
}

controller_interface::return_type ControllerManager::unload_controller(
controller_interface::return_type ControllerManager::cleanup_controller(
const std::string & controller_name)
{
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
std::vector<ControllerSpec> & to = rt_controllers_wrapper_.get_unused_list(guard);
const std::vector<ControllerSpec> & from = rt_controllers_wrapper_.get_updated_list(guard);
RCLCPP_INFO(get_logger(), "Cleanup controller '%s'", controller_name.c_str());

// Transfers the active controllers over, skipping the one to be removed and the active ones.
to = from;
const auto & controllers = get_loaded_controllers();

auto found_it = std::find_if(
to.begin(), to.end(),
controllers.begin(), controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, controller_name));
if (found_it == to.end())

if (found_it == controllers.end())
{
// Fails if we could not remove the controllers
to.clear();
RCLCPP_ERROR(
get_logger(),
"Could not unload controller with name '%s' because no controller with this name exists",
"Could not cleanup controller with name '%s' because no controller with this name exists",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
auto controller = found_it->c;

auto & controller = *found_it;
if (is_controller_unconfigured(controller))
{
// all good nothing to do!
return controller_interface::return_type::OK;
}

if (is_controller_active(*controller.c))
auto state = controller->get_state();
if (
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE ||
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
{
to.clear();
RCLCPP_ERROR(
get_logger(), "Could not unload controller with name '%s' because it is still active",
controller_name.c_str());
get_logger(), "Controller '%s' can not be cleaned-up from '%s' state.",
controller_name.c_str(), state.label().c_str());
return controller_interface::return_type::ERROR;
}
if (controller.c->is_async())

// ASYNCHRONOUS CONTROLLERS: Stop background thread for update
if (controller->is_async())
{
RCLCPP_DEBUG(
get_logger(), "Removing controller '%s' from the list of async controllers",
controller_name.c_str());
async_controller_threads_.erase(controller_name);
}

RCLCPP_DEBUG(get_logger(), "Cleanup controller");
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
if (is_controller_inactive(*controller.c))
// CHAINABLE CONTROLLERS: remove reference interfaces of chainable controllers
if (controller->is_chainable())
{
RCLCPP_DEBUG(
get_logger(), "Controller '%s' is cleaned-up before unloading!", controller_name.c_str());
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
const auto new_state = controller.c->get_node()->cleanup();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
RCLCPP_WARN(
get_logger(), "Failed to clean-up the controller '%s' before unloading!",
controller_name.c_str());
}
get_logger(),
"Controller '%s' is chainable. Interfaces are being removed from resource manager.",
controller_name.c_str());
resource_manager_->remove_controller_reference_interfaces(controller_name);
}

RCLCPP_DEBUG(get_logger(), "Cleanup controller");

auto new_state = controller->get_node()->cleanup();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
RCLCPP_ERROR(
get_logger(), "After cleanup-up, controller '%s' is in state '%s', expected 'unconfigured'.",
controller_name.c_str(), new_state.label().c_str());
return controller_interface::return_type::ERROR;
}

RCLCPP_DEBUG(get_logger(), "Successfully cleaned-up controller '%s'", controller_name.c_str());

return controller_interface::return_type::OK;
}

controller_interface::return_type ControllerManager::unload_controller(
const std::string & controller_name)
{
// first find and clean controller if it is inactive
if (cleanup_controller(controller_name) != controller_interface::return_type::OK)
{
return controller_interface::return_type::ERROR;
}

std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
std::vector<ControllerSpec> & to = rt_controllers_wrapper_.get_unused_list(guard);
const std::vector<ControllerSpec> & from = rt_controllers_wrapper_.get_updated_list(guard);

to = from;
auto found_it = std::find_if(
to.begin(), to.end(),
std::bind(controller_name_compare, std::placeholders::_1, controller_name));
if (found_it == to.end())
{
// Fails if we could not remove the controllers
to.clear();
RCLCPP_ERROR(
get_logger(),
"Could not unload controller with name '%s' because no controller with this name exists",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe the above cleanup controller call should come after this, if not you get the error message of controller not found from cleanup rather than the unload controller


auto & controller = *found_it;

RCLCPP_DEBUG(get_logger(), "Unload controller");
executor_->remove_node(controller.c->get_node()->get_node_base_interface());
to.erase(found_it);

Expand Down Expand Up @@ -728,7 +789,7 @@ controller_interface::return_type ControllerManager::configure_controller(
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
RCLCPP_ERROR(
get_logger(), "After configuring, controller '%s' is in state '%s' , expected inactive.",
get_logger(), "After configuring, controller '%s' is in state '%s', expected 'inactive'.",
controller_name.c_str(), new_state.label().c_str());
return controller_interface::return_type::ERROR;
}
Expand Down Expand Up @@ -1856,6 +1917,21 @@ void ControllerManager::unload_controller_service_cb(
get_logger(), "unloading service finished for controller '%s' ", request->name.c_str());
}

void ControllerManager::cleanup_controller_service_cb(
const std::shared_ptr<controller_manager_msgs::srv::CleanupController::Request> request,
std::shared_ptr<controller_manager_msgs::srv::CleanupController::Response> response)
{
// lock services
RCLCPP_DEBUG(get_logger(), "cleanup service called for controller '%s' ", request->name.c_str());
std::lock_guard<std::mutex> guard(services_lock_);
RCLCPP_DEBUG(get_logger(), "cleanup service locked");

response->ok = cleanup_controller(request->name) == controller_interface::return_type::OK;

RCLCPP_DEBUG(
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Print the cleanup finished message if the response of the clean_controller method is OK. If not, better to print an error or leave the earlier error from within the method

get_logger(), "cleanup service finished for controller '%s' ", request->name.c_str());
}

void ControllerManager::list_hardware_components_srv_cb(
const std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Request>,
std::shared_ptr<controller_manager_msgs::srv::ListHardwareComponents::Response> response)
Expand Down
Loading