Skip to content

Commit

Permalink
readd activate_all_components method to not break API (#1392)
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor authored Feb 14, 2024
1 parent 7ea4f4d commit 55610db
Show file tree
Hide file tree
Showing 2 changed files with 34 additions and 0 deletions.
12 changes: 12 additions & 0 deletions hardware_interface/include/hardware_interface/resource_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,18 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
*/
HardwareReadWriteStatus write(const rclcpp::Time & time, const rclcpp::Duration & period);

/// Activates all available hardware components in the system.
/**
* All available hardware components int the ros2_control framework are activated.
* This is used to preserve default behavior from previous versions where all hardware components
* are activated per default.
*/
[[deprecated(
"The method 'activate_all_components' is deprecated. "
"Use the new 'hardware_components_initial_state' parameter structure to setup the "
"components")]] void
activate_all_components();

/// Checks whether a command interface is registered under the given key.
/**
* \param[in] key string identifying the interface to check.
Expand Down
22 changes: 22 additions & 0 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1387,6 +1387,28 @@ void ResourceManager::validate_storage(
throw std::runtime_error(err_msg);
}
}

// Temporary method to keep old interface and reduce framework changes in the PRs
void ResourceManager::activate_all_components()
{
using lifecycle_msgs::msg::State;
rclcpp_lifecycle::State active_state(
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);

for (auto & component : resource_storage_->actuators_)
{
set_component_state(component.get_name(), active_state);
}
for (auto & component : resource_storage_->sensors_)
{
set_component_state(component.get_name(), active_state);
}
for (auto & component : resource_storage_->systems_)
{
set_component_state(component.get_name(), active_state);
}
}

// END: private methods

} // namespace hardware_interface

0 comments on commit 55610db

Please sign in to comment.