Skip to content

Commit 0ca2ee9

Browse files
authored
[RM] Isolate start and stop interfaces for each Hardware Component (backport #2120) (#2273)
1 parent 57ed164 commit 0ca2ee9

File tree

5 files changed

+189
-107
lines changed

5 files changed

+189
-107
lines changed

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -183,6 +183,7 @@ Changes from `(PR #1688) <https://github.com/ros-controls/ros2_control/pull/1688
183183
* ``Command-/StateInterfaces`` are now created and exported automatically by the framework via the ``on_export_command_interfaces()`` or ``on_export_state_interfaces()`` methods based on the interfaces defined in the ``ros2_control`` XML-tag, which gets parsed and the ``InterfaceDescription`` is created accordingly (check the `hardware_info.hpp <https://github.com/ros-controls/ros2_control/tree/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/hardware_info.hpp>`__).
184184
* The memory for storing the value of a ``Command-/StateInterfaces`` is no longer allocated in the hardware but instead in the ``Command-/StateInterfaces`` itself.
185185
* To access the automatically created ``Command-/StateInterfaces`` we provide the ``std::unordered_map<std::string, InterfaceDescription>``, where the string is the fully qualified name of the interface and the ``InterfaceDescription`` is the configuration of the interface. The ``std::unordered_map<>`` are divided into ``type_state_interfaces_`` and ``type_command_interfaces_`` where type can be: ``joint``, ``sensor``, ``gpio`` and ``unlisted``. E.g. the ``CommandInterfaces`` for all joints can be found in the ``joint_command_interfaces_`` map. The ``unlisted`` includes all interfaces not listed in the ``ros2_control`` XML-tag but were created by overriding the ``export_unlisted_command_interfaces()`` or ``export_unlisted_state_interfaces()`` function by creating some custom ``Command-/StateInterfaces``.
186+
* 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>`_)
186187

187188
ros2controlcli
188189
**************

hardware_interface/include/hardware_interface/actuator_interface.hpp

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -352,12 +352,10 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
352352
*
353353
* \note This is a non-realtime evaluation of whether a set of command interface claims are
354354
* possible, and call to start preparing data structures for the upcoming switch that will occur.
355-
* \note All starting and stopping interface keys are passed to all components, so the function
356-
* should return return_type::OK by default when given interface keys not relevant for this
357-
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
358-
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfaces
359-
* stopping. \return return_type::OK if the new command interface combination can be prepared, or
360-
* if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
355+
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
356+
* \param[in] stop_interfaces vector of string identifiers for the command interfaces stopping.
357+
* \return return_type::OK if the new command interface combination can be prepared (or) if the
358+
* interface key is not relevant to this actuator. Returns return_type::ERROR otherwise.
361359
*/
362360
virtual return_type prepare_command_mode_switch(
363361
const std::vector<std::string> & /*start_interfaces*/,
@@ -371,12 +369,10 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
371369
* Perform the mode-switching for the new command interface combination.
372370
*
373371
* \note This is part of the realtime update loop, and should be fast.
374-
* \note All starting and stopping interface keys are passed to all components, so the function
375-
* should return return_type::OK by default when given interface keys not relevant for this
376-
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
377-
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfaces
378-
* stopping. \return return_type::OK if the new command interface combination can be switched to,
379-
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
372+
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
373+
* \param[in] stop_interfaces vector of string identifiers for the command interfaces stopping.
374+
* \return return_type::OK if the new command interface combination can be switched to (or) if the
375+
* interface key is not relevant to this actuator. Returns return_type::ERROR otherwise.
380376
*/
381377
virtual return_type perform_command_mode_switch(
382378
const std::vector<std::string> & /*start_interfaces*/,

hardware_interface/include/hardware_interface/system_interface.hpp

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -382,12 +382,10 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
382382
*
383383
* \note This is a non-realtime evaluation of whether a set of command interface claims are
384384
* possible, and call to start preparing data structures for the upcoming switch that will occur.
385-
* \note All starting and stopping interface keys are passed to all components, so the function
386-
* should return return_type::OK by default when given interface keys not relevant for this
387-
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
388-
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfaces
389-
* stopping. \return return_type::OK if the new command interface combination can be prepared, or
390-
* if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
385+
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
386+
* \param[in] stop_interfaces vector of string identifiers for the command interfaces stopping.
387+
* \return return_type::OK if the new command interface combination can be prepared (or) if the
388+
* interface key is not relevant to this system. Returns return_type::ERROR otherwise.
391389
*/
392390
virtual return_type prepare_command_mode_switch(
393391
const std::vector<std::string> & /*start_interfaces*/,
@@ -401,12 +399,10 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
401399
* Perform the mode-switching for the new command interface combination.
402400
*
403401
* \note This is part of the realtime update loop, and should be fast.
404-
* \note All starting and stopping interface keys are passed to all components, so the function
405-
* should return return_type::OK by default when given interface keys not relevant for this
406-
* component. \param[in] start_interfaces vector of string identifiers for the command interfaces
407-
* starting. \param[in] stop_interfaces vector of string identifiers for the command interfaces
408-
* stopping. \return return_type::OK if the new command interface combination can be switched to,
409-
* or if the interface key is not relevant to this system. Returns return_type::ERROR otherwise.
402+
* \param[in] start_interfaces vector of string identifiers for the command interfaces starting.
403+
* \param[in] stop_interfaces vector of string identifiers for the command interfaces stopping.
404+
* \return return_type::OK if the new command interface combination can be switched to (or) if the
405+
* interface key is not relevant to this system. Returns return_type::ERROR otherwise.
410406
*/
411407
virtual return_type perform_command_mode_switch(
412408
const std::vector<std::string> & /*start_interfaces*/,

hardware_interface/src/resource_manager.cpp

Lines changed: 86 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,22 @@ std::string interfaces_to_string(
9191
return ss.str();
9292
};
9393

94+
void get_hardware_related_interfaces(
95+
const std::vector<std::string> & hw_command_itfs,
96+
const std::vector<std::string> & start_stop_interfaces_list,
97+
std::vector<std::string> & hw_interfaces)
98+
{
99+
hw_interfaces.clear();
100+
for (const auto & interface : start_stop_interfaces_list)
101+
{
102+
if (
103+
std::find(hw_command_itfs.begin(), hw_command_itfs.end(), interface) != hw_command_itfs.end())
104+
{
105+
hw_interfaces.push_back(interface);
106+
}
107+
}
108+
}
109+
94110
class ResourceStorage
95111
{
96112
static constexpr const char * pkg_name = "hardware_interface";
@@ -672,6 +688,8 @@ class ResourceStorage
672688
auto interfaces = hardware.export_command_interfaces();
673689
hardware_info_map_[hardware.get_name()].command_interfaces =
674690
add_command_interfaces(interfaces);
691+
start_interfaces_buffer_.reserve(start_interfaces_buffer_.capacity() + interfaces.size());
692+
stop_interfaces_buffer_.reserve(stop_interfaces_buffer_.capacity() + interfaces.size());
675693
// TODO(Manuel) END: for backward compatibility
676694
}
677695
catch (const std::exception & ex)
@@ -1306,6 +1324,10 @@ class ResourceStorage
13061324
/// The callback to be called when a component state is switched
13071325
std::function<void()> on_component_state_switch_callback_ = nullptr;
13081326

1327+
// To be used with the prepare and perform command switch for the hardware components
1328+
std::vector<std::string> start_interfaces_buffer_;
1329+
std::vector<std::string> stop_interfaces_buffer_;
1330+
13091331
// Update rate of the controller manager, and the clock interface of its node
13101332
// Used by async components.
13111333
unsigned int cm_update_rate_ = 100;
@@ -1902,12 +1924,24 @@ bool ResourceManager::prepare_command_mode_switch(
19021924
return false;
19031925
}
19041926

1927+
const auto & hardware_info_map = resource_storage_->hardware_info_map_;
19051928
auto call_prepare_mode_switch =
1906-
[&start_interfaces, &stop_interfaces, logger = get_logger()](auto & components)
1929+
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger()](
1930+
auto & components, auto & start_interfaces_buffer, auto & stop_interfaces_buffer)
19071931
{
19081932
bool ret = true;
19091933
for (auto & component : components)
19101934
{
1935+
const auto & hw_command_itfs = hardware_info_map.at(component.get_name()).command_interfaces;
1936+
get_hardware_related_interfaces(hw_command_itfs, start_interfaces, start_interfaces_buffer);
1937+
get_hardware_related_interfaces(hw_command_itfs, stop_interfaces, stop_interfaces_buffer);
1938+
if (start_interfaces_buffer.empty() && stop_interfaces_buffer.empty())
1939+
{
1940+
RCLCPP_DEBUG(
1941+
logger, "Component '%s' after filtering has no command interfaces to switch",
1942+
component.get_name().c_str());
1943+
continue;
1944+
}
19111945
if (
19121946
component.get_lifecycle_state().id() ==
19131947
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
@@ -1917,12 +1951,12 @@ bool ResourceManager::prepare_command_mode_switch(
19171951
{
19181952
if (
19191953
return_type::OK !=
1920-
component.prepare_command_mode_switch(start_interfaces, stop_interfaces))
1954+
component.prepare_command_mode_switch(start_interfaces_buffer, stop_interfaces_buffer))
19211955
{
19221956
RCLCPP_ERROR(
19231957
logger, "Component '%s' did not accept command interfaces combination: \n%s",
19241958
component.get_name().c_str(),
1925-
interfaces_to_string(start_interfaces, stop_interfaces).c_str());
1959+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str());
19261960
ret = false;
19271961
}
19281962
}
@@ -1933,7 +1967,8 @@ bool ResourceManager::prepare_command_mode_switch(
19331967
"Exception of type : %s occurred while preparing command mode switch for component "
19341968
"'%s' for the interfaces: \n %s : %s",
19351969
typeid(e).name(), component.get_name().c_str(),
1936-
interfaces_to_string(start_interfaces, stop_interfaces).c_str(), e.what());
1970+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str(),
1971+
e.what());
19371972
ret = false;
19381973
}
19391974
catch (...)
@@ -1943,16 +1978,27 @@ bool ResourceManager::prepare_command_mode_switch(
19431978
"Unknown exception occurred while preparing command mode switch for component '%s' for "
19441979
"the interfaces: \n %s",
19451980
component.get_name().c_str(),
1946-
interfaces_to_string(start_interfaces, stop_interfaces).c_str());
1981+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str());
19471982
ret = false;
19481983
}
19491984
}
1985+
else
1986+
{
1987+
RCLCPP_WARN(
1988+
logger, "Component '%s' is not in INACTIVE or ACTIVE state, skipping the prepare switch",
1989+
component.get_name().c_str());
1990+
ret = false;
1991+
}
19501992
}
19511993
return ret;
19521994
};
19531995

1954-
const bool actuators_result = call_prepare_mode_switch(resource_storage_->actuators_);
1955-
const bool systems_result = call_prepare_mode_switch(resource_storage_->systems_);
1996+
const bool actuators_result = call_prepare_mode_switch(
1997+
resource_storage_->actuators_, resource_storage_->start_interfaces_buffer_,
1998+
resource_storage_->stop_interfaces_buffer_);
1999+
const bool systems_result = call_prepare_mode_switch(
2000+
resource_storage_->systems_, resource_storage_->start_interfaces_buffer_,
2001+
resource_storage_->stop_interfaces_buffer_);
19562002

19572003
return actuators_result && systems_result;
19582004
}
@@ -1968,12 +2014,24 @@ bool ResourceManager::perform_command_mode_switch(
19682014
return true;
19692015
}
19702016

2017+
const auto & hardware_info_map = resource_storage_->hardware_info_map_;
19712018
auto call_perform_mode_switch =
1972-
[&start_interfaces, &stop_interfaces, logger = get_logger()](auto & components)
2019+
[&start_interfaces, &stop_interfaces, &hardware_info_map, logger = get_logger()](
2020+
auto & components, auto & start_interfaces_buffer, auto & stop_interfaces_buffer)
19732021
{
19742022
bool ret = true;
19752023
for (auto & component : components)
19762024
{
2025+
const auto & hw_command_itfs = hardware_info_map.at(component.get_name()).command_interfaces;
2026+
get_hardware_related_interfaces(hw_command_itfs, start_interfaces, start_interfaces_buffer);
2027+
get_hardware_related_interfaces(hw_command_itfs, stop_interfaces, stop_interfaces_buffer);
2028+
if (start_interfaces_buffer.empty() && stop_interfaces_buffer.empty())
2029+
{
2030+
RCLCPP_DEBUG(
2031+
logger, "Component '%s' after filtering has no command interfaces to perform switch",
2032+
component.get_name().c_str());
2033+
continue;
2034+
}
19772035
if (
19782036
component.get_lifecycle_state().id() ==
19792037
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE ||
@@ -1983,10 +2041,12 @@ bool ResourceManager::perform_command_mode_switch(
19832041
{
19842042
if (
19852043
return_type::OK !=
1986-
component.perform_command_mode_switch(start_interfaces, stop_interfaces))
2044+
component.perform_command_mode_switch(start_interfaces_buffer, stop_interfaces_buffer))
19872045
{
19882046
RCLCPP_ERROR(
1989-
logger, "Component '%s' could not perform switch", component.get_name().c_str());
2047+
logger, "Component '%s' could not perform switch for the command interfaces: \n%s",
2048+
component.get_name().c_str(),
2049+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str());
19902050
ret = false;
19912051
}
19922052
}
@@ -1997,7 +2057,8 @@ bool ResourceManager::perform_command_mode_switch(
19972057
"Exception of type : %s occurred while performing command mode switch for component "
19982058
"'%s' for the interfaces: \n %s : %s",
19992059
typeid(e).name(), component.get_name().c_str(),
2000-
interfaces_to_string(start_interfaces, stop_interfaces).c_str(), e.what());
2060+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str(),
2061+
e.what());
20012062
ret = false;
20022063
}
20032064
catch (...)
@@ -2008,16 +2069,27 @@ bool ResourceManager::perform_command_mode_switch(
20082069
"for "
20092070
"the interfaces: \n %s",
20102071
component.get_name().c_str(),
2011-
interfaces_to_string(start_interfaces, stop_interfaces).c_str());
2072+
interfaces_to_string(start_interfaces_buffer, stop_interfaces_buffer).c_str());
20122073
ret = false;
20132074
}
20142075
}
2076+
else
2077+
{
2078+
RCLCPP_WARN(
2079+
logger, "Component '%s' is not in INACTIVE or ACTIVE state, skipping the perform switch",
2080+
component.get_name().c_str());
2081+
ret = false;
2082+
}
20152083
}
20162084
return ret;
20172085
};
20182086

2019-
const bool actuators_result = call_perform_mode_switch(resource_storage_->actuators_);
2020-
const bool systems_result = call_perform_mode_switch(resource_storage_->systems_);
2087+
const bool actuators_result = call_perform_mode_switch(
2088+
resource_storage_->actuators_, resource_storage_->start_interfaces_buffer_,
2089+
resource_storage_->stop_interfaces_buffer_);
2090+
const bool systems_result = call_perform_mode_switch(
2091+
resource_storage_->systems_, resource_storage_->start_interfaces_buffer_,
2092+
resource_storage_->stop_interfaces_buffer_);
20212093

20222094
if (actuators_result && systems_result)
20232095
{

0 commit comments

Comments
 (0)