Skip to content

Commit 55610db

Browse files
authored
readd activate_all_components method to not break API (#1392)
1 parent 7ea4f4d commit 55610db

File tree

2 files changed

+34
-0
lines changed

2 files changed

+34
-0
lines changed

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -387,6 +387,18 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
387387
*/
388388
HardwareReadWriteStatus write(const rclcpp::Time & time, const rclcpp::Duration & period);
389389

390+
/// Activates all available hardware components in the system.
391+
/**
392+
* All available hardware components int the ros2_control framework are activated.
393+
* This is used to preserve default behavior from previous versions where all hardware components
394+
* are activated per default.
395+
*/
396+
[[deprecated(
397+
"The method 'activate_all_components' is deprecated. "
398+
"Use the new 'hardware_components_initial_state' parameter structure to setup the "
399+
"components")]] void
400+
activate_all_components();
401+
390402
/// Checks whether a command interface is registered under the given key.
391403
/**
392404
* \param[in] key string identifying the interface to check.

hardware_interface/src/resource_manager.cpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1387,6 +1387,28 @@ void ResourceManager::validate_storage(
13871387
throw std::runtime_error(err_msg);
13881388
}
13891389
}
1390+
1391+
// Temporary method to keep old interface and reduce framework changes in the PRs
1392+
void ResourceManager::activate_all_components()
1393+
{
1394+
using lifecycle_msgs::msg::State;
1395+
rclcpp_lifecycle::State active_state(
1396+
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
1397+
1398+
for (auto & component : resource_storage_->actuators_)
1399+
{
1400+
set_component_state(component.get_name(), active_state);
1401+
}
1402+
for (auto & component : resource_storage_->sensors_)
1403+
{
1404+
set_component_state(component.get_name(), active_state);
1405+
}
1406+
for (auto & component : resource_storage_->systems_)
1407+
{
1408+
set_component_state(component.get_name(), active_state);
1409+
}
1410+
}
1411+
13901412
// END: private methods
13911413

13921414
} // namespace hardware_interface

0 commit comments

Comments
 (0)