Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Handle SIGINT properly in the controller manager (backport #2014) #2040

Merged
merged 3 commits into from
Feb 7, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,14 @@ class ControllerManager : public rclcpp::Node
const rclcpp::NodeOptions & options = get_cm_node_options());

CONTROLLER_MANAGER_PUBLIC
bmagyar marked this conversation as resolved.
Show resolved Hide resolved
virtual ~ControllerManager() = default;
virtual ~ControllerManager();

/// Shutdown all controllers in the controller manager.
/**
* \return true if all controllers are successfully shutdown, false otherwise.
*/
CONTROLLER_MANAGER_PUBLIC
bool shutdown_controllers();

CONTROLLER_MANAGER_PUBLIC
void robot_description_callback(const std_msgs::msg::String & msg);
Expand Down Expand Up @@ -475,6 +482,7 @@ class ControllerManager : public rclcpp::Node
int used_by_realtime_controllers_index_ = -1;
};

std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{nullptr};
RTControllerListWrapper rt_controllers_wrapper_;
/// mutex copied from ROS1 Control, protects service callbacks
/// not needed if we're guaranteed that the callbacks don't come from multiple threads
Expand Down
69 changes: 69 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,12 @@ static const rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = {
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false};

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_inactive(const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
Expand Down Expand Up @@ -322,6 +328,46 @@ ControllerManager::ControllerManager(
}
}

ControllerManager::~ControllerManager()
{
if (preshutdown_cb_handle_)
{
rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context();
context->remove_pre_shutdown_callback(*(preshutdown_cb_handle_.get()));
preshutdown_cb_handle_.reset();
}
}

bool ControllerManager::shutdown_controllers()
{
RCLCPP_INFO(get_logger(), "Shutting down all controllers in the controller manager.");
// Shutdown all controllers
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
std::vector<ControllerSpec> controllers_list = rt_controllers_wrapper_.get_updated_list(guard);
bool ctrls_shutdown_status = true;
for (auto & controller : controllers_list)
{
if (is_controller_active(controller.c))
{
RCLCPP_INFO(
get_logger(), "Deactivating controller '%s'", controller.c->get_node()->get_name());
controller.c->get_node()->deactivate();
controller.c->release_interfaces();
}
if (is_controller_inactive(*controller.c) || is_controller_unconfigured(*controller.c))
{
RCLCPP_INFO(
get_logger(), "Shutting down controller '%s'", controller.c->get_node()->get_name());
controller.c->get_node()->shutdown();
}
ctrls_shutdown_status &=
(controller.c->get_node()->get_current_state().id() ==
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
executor_->remove_node(controller.c->get_node()->get_node_base_interface());
}
return ctrls_shutdown_status;
}

void ControllerManager::subscribe_to_robot_description_topic()
{
// set QoS to transient local to get messages that have already been published
Expand Down Expand Up @@ -529,6 +575,29 @@ void ControllerManager::init_services()
"~/set_hardware_component_state",
std::bind(&ControllerManager::set_hardware_component_state_srv_cb, this, _1, _2),
rmw_qos_profile_services_hist_keep_all, best_effort_callback_group_);

// Add on_shutdown callback to stop the controller manager
rclcpp::Context::SharedPtr context = this->get_node_base_interface()->get_context();
preshutdown_cb_handle_ =
std::make_unique<rclcpp::PreShutdownCallbackHandle>(context->add_pre_shutdown_callback(
[this]()
{
RCLCPP_INFO(get_logger(), "Shutdown request received....");
if (this->get_node_base_interface()->get_associated_with_executor_atomic().load())
{
executor_->remove_node(this->get_node_base_interface());
}
executor_->cancel();
if (!this->shutdown_controllers())
{
RCLCPP_ERROR(get_logger(), "Failed shutting down the controllers.");
}
if (!resource_manager_->shutdown_components())
{
RCLCPP_ERROR(get_logger(), "Failed shutting down hardware components.");
}
RCLCPP_INFO(get_logger(), "Shutting down the controller manager.");
}));
}

controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_controller(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,13 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager

~ResourceManager();

/// Shutdown all hardware components, irrespective of their state.
/**
* The method is called when the controller manager is being shutdown.
* @return true if all hardware components are successfully shutdown, false otherwise.
*/
bool shutdown_components();

/// Load resources from on a given URDF.
/**
* The resource manager can be post initialized with a given URDF.
Expand Down
18 changes: 17 additions & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -397,7 +397,7 @@ class ResourceStorage
result = shutdown_hardware(hardware);
break;
case State::PRIMARY_STATE_ACTIVE:
result = shutdown_hardware(hardware);
result = deactivate_hardware(hardware) && shutdown_hardware(hardware);
break;
case State::PRIMARY_STATE_FINALIZED:
result = true;
Expand Down Expand Up @@ -675,6 +675,22 @@ ResourceManager::ResourceManager(
}
}

bool ResourceManager::shutdown_components()
{
std::unique_lock<std::recursive_mutex> guard(resource_interfaces_lock_);
bool shutdown_status = true;
for (auto const & hw_info : resource_storage_->hardware_info_map_)
{
rclcpp_lifecycle::State finalized_state(
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED);
if (set_component_state(hw_info.first, finalized_state) != return_type::OK)
{
shutdown_status = false;
}
}
return shutdown_status;
}

// CM API: Called in "callback/slow"-thread
void ResourceManager::load_urdf(
const std::string & urdf, bool validate_interfaces, bool load_and_initialize_components)
Expand Down
Loading