-
-
Notifications
You must be signed in to change notification settings - Fork 39
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #144 from sviatoslav-zapolskyi/joint_state_publish…
…er_gui Add joint_state_publisher_gui pkg for osx arm64
- Loading branch information
Showing
15 changed files
with
57 additions
and
0 deletions.
There are no files selected for viewing
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,56 @@ | ||
diff --git a/hardware_interface/include/hardware_interface/resource_manager.hpp b/hardware_interface/include/hardware_interface/resource_manager.hpp | ||
index 01c837259f..e94bf5f6ab 100644 | ||
--- a/hardware_interface/include/hardware_interface/resource_manager.hpp | ||
+++ b/hardware_interface/include/hardware_interface/resource_manager.hpp | ||
@@ -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. | ||
diff --git a/hardware_interface/src/resource_manager.cpp b/hardware_interface/src/resource_manager.cpp | ||
index 2c6fd8a305..e585571d35 100644 | ||
--- a/hardware_interface/src/resource_manager.cpp | ||
+++ b/hardware_interface/src/resource_manager.cpp | ||
@@ -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 |
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters