Skip to content

Commit bb87986

Browse files
authored
Add parameter to allow controllers with inactive hardware components (#2501)
1 parent ff52562 commit bb87986

File tree

7 files changed

+389
-21
lines changed

7 files changed

+389
-21
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 8 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -393,21 +393,8 @@ rclcpp::NodeOptions get_cm_node_options()
393393
ControllerManager::ControllerManager(
394394
std::shared_ptr<rclcpp::Executor> executor, const std::string & manager_node_name,
395395
const std::string & node_namespace, const rclcpp::NodeOptions & options)
396-
: rclcpp::Node(manager_node_name, node_namespace, options),
397-
diagnostics_updater_(this),
398-
executor_(executor),
399-
loader_(
400-
std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
401-
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
402-
chainable_loader_(
403-
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
404-
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
405-
cm_node_options_(options)
396+
: ControllerManager(executor, "", false, manager_node_name, node_namespace, options)
406397
{
407-
initialize_parameters();
408-
resource_manager_ =
409-
std::make_unique<hardware_interface::ResourceManager>(trigger_clock_, this->get_logger());
410-
init_controller_manager();
411398
}
412399

413400
ControllerManager::ControllerManager(
@@ -428,13 +415,18 @@ ControllerManager::ControllerManager(
428415
{
429416
initialize_parameters();
430417
hardware_interface::ResourceManagerParams params;
431-
params.robot_description = urdf;
418+
params.robot_description = robot_description_;
432419
params.clock = trigger_clock_;
433420
params.logger = this->get_logger();
434421
params.activate_all = activate_all_hw_components;
435422
params.update_rate = static_cast<unsigned int>(params_->update_rate);
436423
params.executor = executor_;
437-
resource_manager_ = std::make_unique<hardware_interface::ResourceManager>(params, true);
424+
params.allow_controller_activation_with_inactive_hardware =
425+
params_->defaults.allow_controller_activation_with_inactive_hardware;
426+
params.return_failed_hardware_names_on_return_deactivate_write_cycle_ =
427+
params_->defaults.deactivate_controllers_on_hardware_self_deactivate;
428+
resource_manager_ =
429+
std::make_unique<hardware_interface::ResourceManager>(params, !robot_description_.empty());
438430
init_controller_manager();
439431
}
440432

controller_manager/src/controller_manager_parameters.yaml

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,23 @@ controller_manager:
5454
}
5555
}
5656

57+
allow_controller_activation_with_inactive_hardware: {
58+
type: bool,
59+
default_value: false,
60+
read_only: true,
61+
description: "If true, controllers are allowed to claim resources from inactive hardware components. If false, controllers can only claim resources from active hardware components. \
62+
However, it is not recommended to set this parameter to true for the safety reasons with the hardware and unexpected movement, this is purely added for backward compatibility.",
63+
}
64+
65+
deactivate_controllers_on_hardware_self_deactivate: {
66+
type: bool,
67+
default_value: true,
68+
read_only: true,
69+
description: "If set to true, when a hardware component returns DEACTIVATE on the write cycle, controllers using those interfaces will be deactivated. When set to false, controllers using \
70+
those interfaces will continue to run. It is not recommended to set this parameter to false for safety reasons with hardware. This will be the default behaviour of the controller \
71+
manager and this parameter will be removed in future releases. Please use with caution.",
72+
}
73+
5774
diagnostics:
5875
threshold:
5976
controller_manager:

doc/release_notes.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,9 @@ controller_manager
1414
hardware_interface
1515
******************
1616
* The ``prepare_command_mode_switch`` and ``perform_command_mode_switch`` methods will now only receive the start/stop interfaces that belong to the hardware component instead of everything (`#2120 <https://github.com/ros-controls/ros2_control/pull/2120>`_)
17+
* The hardware interface is now treated similarly as ERROR, when a hardware component returns ERROR on the read cycle (`#2334 <https://github.com/ros-controls/ros2_control/pull/2334>`_).
18+
* The controllers are now deactivated when a hardware component returns DEACTIVATE on the write cycle. The parameter ``deactivate_controllers_on_hardware_self_deactivate`` is added to control this behavior temporarily. It is recommended to set this parameter to true in order to avoid controllers to use inactive hardware components and to avoid any unexpected behavior. This feature parameter will be removed in future releases and will be defaulted to true (`#2334 <https://github.com/ros-controls/ros2_control/pull/2334>`_ & `#2501 <https://github.com/ros-controls/ros2_control/pull/2501>`_).
19+
* The controllers are not allowed to be activated when the hardware component is in INACTIVE state. The parameter ``allow_controller_activation_with_inactive_hardware`` is added to control this behavior temporarily. It is recommended to set this parameter to false in order to avoid controllers to use inactive hardware components and to avoid any unexpected behavior. This feature parameter will be removed in future releases and will be defaulted to false (`#2347 <https://github.com/ros-controls/ros2_control/pull/2347>`_).
1720

1821
ros2controlcli
1922
**************

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -631,6 +631,8 @@ class ResourceManager
631631
rclcpp::Clock::SharedPtr get_clock() const;
632632

633633
bool components_are_loaded_and_initialized_ = false;
634+
bool allow_controller_activation_with_inactive_hardware_ = false;
635+
bool return_failed_hardware_names_on_return_deactivate_write_cycle_ = true;
634636

635637
mutable std::recursive_mutex resource_interfaces_lock_;
636638
mutable std::recursive_mutex claimed_command_interfaces_lock_;

hardware_interface/include/hardware_interface/types/resource_manager_params.hpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,29 @@ struct ResourceManagerParams
6161
*/
6262
bool activate_all = false;
6363

64+
/**
65+
* @brief If true, controllers are allowed to claim resources from inactive hardware components.
66+
* If false, controllers can only claim resources from active hardware components.
67+
* Moreover, when the hardware component returns DEACTIVATE on read/write cycle: If set to true,
68+
* the controllers using those interfaces will continue to run. If set to false, the controllers
69+
* using those interfaces will be deactivated.
70+
* @warning Allowing control with inactive hardware is not recommended for safety reasons.
71+
* Use with caution only if you really know what you are doing.
72+
* @note This parameter might be deprecated or removed in the future releases. Please use with
73+
* caution.
74+
*/
75+
bool allow_controller_activation_with_inactive_hardware = false;
76+
77+
/**
78+
* @brief If true, when a hardware component returns DEACTIVATE on the write cycle,
79+
* its name will be included in the returned HardwareReadWriteStatus.failed_hardware_names list.
80+
* If false, the names of such hardware components will not be included in that list.
81+
* This can be useful when controllers are allowed to operate with inactive hardware components.
82+
* @note This parameter might be deprecated or removed in future releases. Please use with
83+
* caution.
84+
*/
85+
bool return_failed_hardware_names_on_return_deactivate_write_cycle_ = true;
86+
6487
/**
6588
* @brief The update rate (in Hz) of the ControllerManager.
6689
* This can be used by ResourceManager to configure asynchronous hardware components

hardware_interface/src/resource_manager.cpp

Lines changed: 32 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1397,6 +1397,22 @@ ResourceManager::ResourceManager(
13971397
const hardware_interface::ResourceManagerParams & params, bool load)
13981398
: resource_storage_(std::make_unique<ResourceStorage>(params.clock, params.logger))
13991399
{
1400+
RCLCPP_WARN_EXPRESSION(
1401+
params.logger, params.allow_controller_activation_with_inactive_hardware,
1402+
"The parameter 'allow_controller_activation_with_inactive_hardware' is set to true. It is "
1403+
"recommended to use the settings to false in order to avoid controllers to use inactive "
1404+
"hardware components and to avoid any unexpected behavior. This feature might be removed in "
1405+
"future releases and will be defaulted to false.");
1406+
RCLCPP_WARN_EXPRESSION(
1407+
params.logger, !params.return_failed_hardware_names_on_return_deactivate_write_cycle_,
1408+
"The parameter 'deactivate_controllers_on_hardware_self_deactivate' is set to false. It is "
1409+
"recommended to use the settings to true in order to avoid controllers to use inactive "
1410+
"hardware components and to avoid any unexpected behavior. This feature might be removed in "
1411+
"future releases and will be defaulted to true.");
1412+
allow_controller_activation_with_inactive_hardware_ =
1413+
params.allow_controller_activation_with_inactive_hardware;
1414+
return_failed_hardware_names_on_return_deactivate_write_cycle_ =
1415+
params.return_failed_hardware_names_on_return_deactivate_write_cycle_;
14001416
if (load)
14011417
{
14021418
load_and_initialize_components(params);
@@ -2006,7 +2022,9 @@ bool ResourceManager::prepare_command_mode_switch(
20062022

20072023
const auto & hardware_info_map = resource_storage_->hardware_info_map_;
20082024
auto call_prepare_mode_switch =
2009-
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger()](
2025+
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger(),
2026+
allow_controller_activation_with_inactive_hardware =
2027+
allow_controller_activation_with_inactive_hardware_](
20102028
auto & components, auto & start_interfaces_buffer, auto & stop_interfaces_buffer)
20112029
{
20122030
bool ret = true;
@@ -2024,7 +2042,9 @@ bool ResourceManager::prepare_command_mode_switch(
20242042
}
20252043
if (
20262044
!start_interfaces_buffer.empty() &&
2027-
component.get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
2045+
component.get_lifecycle_state().id() ==
2046+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE &&
2047+
!allow_controller_activation_with_inactive_hardware)
20282048
{
20292049
RCLCPP_WARN(
20302050
logger, "Component '%s' is in INACTIVE state, but has start interfaces to switch: \n%s",
@@ -2106,7 +2126,9 @@ bool ResourceManager::perform_command_mode_switch(
21062126

21072127
const auto & hardware_info_map = resource_storage_->hardware_info_map_;
21082128
auto call_perform_mode_switch =
2109-
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger()](
2129+
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger(),
2130+
allow_controller_activation_with_inactive_hardware =
2131+
allow_controller_activation_with_inactive_hardware_](
21102132
auto & components, auto & start_interfaces_buffer, auto & stop_interfaces_buffer)
21112133
{
21122134
bool ret = true;
@@ -2124,7 +2146,9 @@ bool ResourceManager::perform_command_mode_switch(
21242146
}
21252147
if (
21262148
!start_interfaces_buffer.empty() &&
2127-
component.get_lifecycle_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
2149+
component.get_lifecycle_state().id() ==
2150+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE &&
2151+
!allow_controller_activation_with_inactive_hardware)
21282152
{
21292153
RCLCPP_WARN(
21302154
logger, "Component '%s' is in INACTIVE state, but has start interfaces to switch: \n%s",
@@ -2507,7 +2531,10 @@ HardwareReadWriteStatus ResourceManager::write(
25072531
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE);
25082532
set_component_state(component_name, inactive_state);
25092533
read_write_status.result = ret_val;
2510-
read_write_status.failed_hardware_names.push_back(component_name);
2534+
if (return_failed_hardware_names_on_return_deactivate_write_cycle_)
2535+
{
2536+
read_write_status.failed_hardware_names.push_back(component_name);
2537+
}
25112538
}
25122539
}
25132540
};

0 commit comments

Comments
 (0)