From d5fb0de815c7f73b3463d30672075e6895df8a01 Mon Sep 17 00:00:00 2001 From: RobertWilbrandt Date: Wed, 9 Oct 2024 17:08:43 +0200 Subject: [PATCH 1/2] Add `PoseSensor` semantic component (#1775) (cherry picked from commit 8cdded3a4a7fed085dc824bbebe4960f80cdf2b9) # Conflicts: # doc/release_notes.rst --- controller_interface/CMakeLists.txt | 10 ++ .../semantic_components/pose_sensor.hpp | 110 ++++++++++++++ controller_interface/package.xml | 1 + .../test/test_pose_sensor.cpp | 98 +++++++++++++ .../test/test_pose_sensor.hpp | 59 ++++++++ doc/release_notes.rst | 137 ++++++++++++++++++ 6 files changed, 415 insertions(+) create mode 100644 controller_interface/include/semantic_components/pose_sensor.hpp create mode 100644 controller_interface/test/test_pose_sensor.cpp create mode 100644 controller_interface/test/test_pose_sensor.hpp diff --git a/controller_interface/CMakeLists.txt b/controller_interface/CMakeLists.txt index 88a54d5c7a..8deea4954e 100644 --- a/controller_interface/CMakeLists.txt +++ b/controller_interface/CMakeLists.txt @@ -32,6 +32,7 @@ target_compile_definitions(controller_interface PRIVATE "CONTROLLER_INTERFACE_BU if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) + find_package(geometry_msgs REQUIRED) find_package(sensor_msgs REQUIRED) ament_add_gmock(test_controller_interface test/test_controller_interface.cpp) @@ -70,6 +71,15 @@ if(BUILD_TESTING) ament_target_dependencies(test_imu_sensor sensor_msgs ) + + ament_add_gmock(test_pose_sensor test/test_pose_sensor.cpp) + target_link_libraries(test_pose_sensor + controller_interface + hardware_interface::hardware_interface + ) + ament_target_dependencies(test_pose_sensor + geometry_msgs + ) endif() install( diff --git a/controller_interface/include/semantic_components/pose_sensor.hpp b/controller_interface/include/semantic_components/pose_sensor.hpp new file mode 100644 index 0000000000..60dbecd718 --- /dev/null +++ b/controller_interface/include/semantic_components/pose_sensor.hpp @@ -0,0 +1,110 @@ +// Copyright 2024 FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ +#define SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ + +#include +#include +#include + +#include "geometry_msgs/msg/pose.hpp" +#include "semantic_components/semantic_component_interface.hpp" + +namespace semantic_components +{ + +class PoseSensor : public SemanticComponentInterface +{ +public: + /// Constructor for a standard pose sensor with interface names set based on sensor name. + explicit PoseSensor(const std::string & name) : SemanticComponentInterface{name, 7} + { + // Use standard interface names + interface_names_.emplace_back(name_ + '/' + "position.x"); + interface_names_.emplace_back(name_ + '/' + "position.y"); + interface_names_.emplace_back(name_ + '/' + "position.z"); + interface_names_.emplace_back(name_ + '/' + "orientation.x"); + interface_names_.emplace_back(name_ + '/' + "orientation.y"); + interface_names_.emplace_back(name_ + '/' + "orientation.z"); + interface_names_.emplace_back(name_ + '/' + "orientation.w"); + + // Set all sensor values to default value NaN + std::fill(position_.begin(), position_.end(), std::numeric_limits::quiet_NaN()); + std::fill(orientation_.begin(), orientation_.end(), std::numeric_limits::quiet_NaN()); + } + + virtual ~PoseSensor() = default; + + /// Update and return position. + /*! + * Update and return current pose position from state interfaces. + * + * \return Array of position coordinates. + */ + std::array get_position() + { + for (size_t i = 0; i < 3; ++i) + { + position_[i] = state_interfaces_[i].get().get_value(); + } + + return position_; + } + + /// Update and return orientation + /*! + * Update and return current pose orientation from state interfaces. + * + * \return Array of orientation coordinates in xyzw convention. + */ + std::array get_orientation() + { + for (size_t i = 3; i < 7; ++i) + { + orientation_[i - 3] = state_interfaces_[i].get().get_value(); + } + + return orientation_; + } + + /// Fill pose message with current values. + /** + * Fill a pose message with current position and orientation from the state interfaces. + */ + bool get_values_as_message(geometry_msgs::msg::Pose & message) + { + // Update state from state interfaces + get_position(); + get_orientation(); + + // Set message values from current state + message.position.x = position_[0]; + message.position.y = position_[1]; + message.position.z = position_[2]; + message.orientation.x = orientation_[0]; + message.orientation.y = orientation_[1]; + message.orientation.z = orientation_[2]; + message.orientation.w = orientation_[3]; + + return true; + } + +protected: + std::array position_; + std::array orientation_; +}; + +} // namespace semantic_components + +#endif // SEMANTIC_COMPONENTS__POSE_SENSOR_HPP_ diff --git a/controller_interface/package.xml b/controller_interface/package.xml index c473c91b1e..86061a7e05 100644 --- a/controller_interface/package.xml +++ b/controller_interface/package.xml @@ -18,6 +18,7 @@ rclcpp_lifecycle ament_cmake_gmock + geometry_msgs sensor_msgs diff --git a/controller_interface/test/test_pose_sensor.cpp b/controller_interface/test/test_pose_sensor.cpp new file mode 100644 index 0000000000..1ceb7c32a6 --- /dev/null +++ b/controller_interface/test/test_pose_sensor.cpp @@ -0,0 +1,98 @@ +// Copyright (c) 2024, FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#include "test_pose_sensor.hpp" + +void PoseSensorTest::SetUp() +{ + full_interface_names_.reserve(size_); + for (const auto & interface_name : interface_names_) + { + full_interface_names_.emplace_back(sensor_name_ + '/' + interface_name); + } +} + +void PoseSensorTest::TearDown() { pose_sensor_.reset(nullptr); } + +TEST_F(PoseSensorTest, validate_all) +{ + // Create sensor + pose_sensor_ = std::make_unique(sensor_name_); + EXPECT_EQ(pose_sensor_->name_, sensor_name_); + + // Validate reserved space for interface_names_ and state_interfaces_ + // As state_interfaces_ are not defined yet, use capacity() + ASSERT_EQ(pose_sensor_->interface_names_.size(), size_); + ASSERT_EQ(pose_sensor_->state_interfaces_.capacity(), size_); + + // Validate default interface_names_ + EXPECT_TRUE(std::equal( + pose_sensor_->interface_names_.cbegin(), pose_sensor_->interface_names_.cend(), + full_interface_names_.cbegin(), full_interface_names_.cend())); + + // Get interface names + std::vector interface_names = pose_sensor_->get_state_interface_names(); + + // Assign values to position + hardware_interface::StateInterface position_x{ + sensor_name_, interface_names_[0], &position_values_[0]}; + hardware_interface::StateInterface position_y{ + sensor_name_, interface_names_[1], &position_values_[1]}; + hardware_interface::StateInterface position_z{ + sensor_name_, interface_names_[2], &position_values_[2]}; + + // Assign values to orientation + hardware_interface::StateInterface orientation_x{ + sensor_name_, interface_names_[3], &orientation_values_[0]}; + hardware_interface::StateInterface orientation_y{ + sensor_name_, interface_names_[4], &orientation_values_[1]}; + hardware_interface::StateInterface orientation_z{ + sensor_name_, interface_names_[5], &orientation_values_[2]}; + hardware_interface::StateInterface orientation_w{ + sensor_name_, interface_names_[6], &orientation_values_[3]}; + + // Create state interface vector in jumbled order + std::vector temp_state_interfaces; + temp_state_interfaces.reserve(7); + + temp_state_interfaces.emplace_back(position_z); + temp_state_interfaces.emplace_back(orientation_y); + temp_state_interfaces.emplace_back(orientation_x); + temp_state_interfaces.emplace_back(position_x); + temp_state_interfaces.emplace_back(orientation_w); + temp_state_interfaces.emplace_back(position_y); + temp_state_interfaces.emplace_back(orientation_z); + + // Assign interfaces + pose_sensor_->assign_loaned_state_interfaces(temp_state_interfaces); + EXPECT_EQ(pose_sensor_->state_interfaces_.size(), size_); + + // Validate correct position and orientation + EXPECT_EQ(pose_sensor_->get_position(), position_values_); + EXPECT_EQ(pose_sensor_->get_orientation(), orientation_values_); + + // Validate generated message + geometry_msgs::msg::Pose temp_message; + ASSERT_TRUE(pose_sensor_->get_values_as_message(temp_message)); + EXPECT_EQ(temp_message.position.x, position_values_[0]); + EXPECT_EQ(temp_message.position.y, position_values_[1]); + EXPECT_EQ(temp_message.position.z, position_values_[2]); + EXPECT_EQ(temp_message.orientation.x, orientation_values_[0]); + EXPECT_EQ(temp_message.orientation.y, orientation_values_[1]); + EXPECT_EQ(temp_message.orientation.z, orientation_values_[2]); + EXPECT_EQ(temp_message.orientation.w, orientation_values_[3]); + + // Release state interfaces + pose_sensor_->release_interfaces(); + ASSERT_EQ(pose_sensor_->state_interfaces_.size(), 0); +} diff --git a/controller_interface/test/test_pose_sensor.hpp b/controller_interface/test/test_pose_sensor.hpp new file mode 100644 index 0000000000..c2344caaa2 --- /dev/null +++ b/controller_interface/test/test_pose_sensor.hpp @@ -0,0 +1,59 @@ +// Copyright (c) 2024, FZI Forschungszentrum Informatik +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TEST_POSE_SENSOR_HPP_ +#define TEST_POSE_SENSOR_HPP_ + +#include + +#include +#include +#include +#include + +#include "semantic_components/pose_sensor.hpp" + +class TestablePoseSensor : public semantic_components::PoseSensor +{ + FRIEND_TEST(PoseSensorTest, validate_all); + +public: + // Use default interface names + explicit TestablePoseSensor(const std::string & name) : PoseSensor{name} {} + + virtual ~TestablePoseSensor() = default; +}; + +class PoseSensorTest : public ::testing::Test +{ +public: + void SetUp(); + void TearDown(); + +protected: + const size_t size_ = 7; + const std::string sensor_name_ = "test_pose_sensor"; + + std::vector full_interface_names_; + const std::vector interface_names_ = { + "position.x", "position.y", "position.z", "orientation.x", + "orientation.y", "orientation.z", "orientation.w"}; + + std::array position_values_ = {{1.1, 2.2, 3.3}}; + std::array orientation_values_ = {{4.4, 5.5, 6.6, 7.7}}; + + std::unique_ptr pose_sensor_; +}; + +#endif // TEST_POSE_SENSOR_HPP_ diff --git a/doc/release_notes.rst b/doc/release_notes.rst index 722d0aea74..ce72aca386 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -6,4 +6,141 @@ This list summarizes the changes between Humble (previous) and Iron (current) re .. note:: +<<<<<<< HEAD This list was created in July 2024, earlier changes may not be included. +======= + .. code-block:: cpp + + #include + ... + RCLCPP_INFO(get_logger(), "controller_manager version: %s", CONTROLLER_MANAGER_VERSION_STR); + +controller_interface +******************** +For details see the controller_manager section. + +* Pass URDF to controllers on init (`#1088 `_). +* Pass controller manager update rate on the init of the controller interface (`#1141 `_) +* A method to get node options to setup the controller node #api-breaking (`#1169 `_) +* Export state interfaces from the chainable controller #api-breaking (`#1021 `_) +* All chainable controllers must implement the method ``export_state_interfaces`` to export the state interfaces, similar to ``export_reference_interfaces`` method that is exporting the reference interfaces. +* The controllers will now set ``use_global_arguments`` from `NodeOptions `__ to false, to avoid getting influenced by global arguments (Issue : `#1684 `_) (`#1694 `_). From now on, in order to set the parameters to the controller, the ``--param-file`` option from spawner should be used. +* With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. +* The ``assign_interfaces`` and ``release_interfaces`` methods are now virtual, so that the user can override them to store the interfaces into custom variable types, so that the user can have the flexibility to take the ownership of the loaned interfaces to the controller (`#1743 `_) +* The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 `_) + +controller_manager +****************** +* URDF is now passed to controllers on init (`#1088 `_) + This should help avoiding extra legwork in controllers to get access to the ``/robot_description``. +* Pass controller manager update rate on the init of the controller interface (`#1141 `_) +* Report inactive controllers as a diagnostics ok instead of an error (`#1184 `_) +* Set chained controller interfaces 'available' for activated controllers (`#1098 `_) + + * Configured chainable controller: Listed exported interfaces are unavailable and unclaimed + * Active chainable controller (not in chained mode): Listed exported interfaces are available but unclaimed + * Active chainable controller (in chained mode): Listed exported interfaces are available and claimed +* Try using SCHED_FIFO on any kernel (`#1142 `_) +* A method to get node options to setup the controller node was added (`#1169 `_): ``get_node_options`` can be overridden by controllers, this would make it easy for other controllers to be able to setup their own custom node options +* CM now subscribes to ``robot_description`` topic instead of ``~/robot_description`` (`#1410 `_). +* Change the controller sorting with an approach similar to directed acyclic graphs (`#1384 `_) +* Changes from `(PR #1256) `__ + + * All ``joints`` defined in the ````-tag have to be present in the URDF received :ref:`by the controller manager `, otherwise the following error is shown: + + The published robot description file (URDF) seems not to be genuine. The following error was caught: not found in URDF. + + This is to ensure that the URDF and the ````-tag are consistent. E.g., for configuration ports use ``gpio`` interface types instead. + + * The syntax for mimic joints is changed to the `official URDF specification `__. + + .. code-block:: xml + + + + + + + + + + + + + + + + + + The parameters within the ``ros2_control`` tag are not supported any more. +* The support for the ``description`` parameter for loading the URDF was removed (`#1358 `_). +* The ``--controller-type`` or ``-t`` spawner arg is removed. Now the controller type is defined in the controller configuration file with ``type`` field (`#1639 `_). +* The ``--namespace`` or ``-n`` spawner arg is deprecated. Now the spawner namespace can be defined using the ROS 2 standard way (`#1640 `_). + +hardware_interface +****************** +* A portable version for string-to-double conversion was added: ``hardware_interface::stod`` (`#1257 `_) +* ``test_components`` was moved to its own package (`#1325 `_) +* The ``ros2_control`` tag now supports parsing of the limits from the URDF into the ``HardwareInfo`` structure. More conservative limits can be defined using the ``min`` and ``max`` attributes per interface (`#1472 `_) + + .. code:: xml + + + + ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware + 2.0 + 3.0 + 2.0 + + + + -1 + 1 + + + + + + + + +* Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 `_) +* Access to logger and clock through ``get_logger`` and ``get_clock`` methods in ResourceManager and HardwareComponents ``Actuator``, ``Sensor`` and ``System`` (`#1585 `_) +* Added ``get_hardware_info`` method to the hardware components interface to access the ``HardwareInfo`` instead of accessing the variable ``info_`` directly (`#1643 `_) +* With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. +* With (`#1421 `_) a key-value storage is added to InterfaceInfo. This allows to define extra params with per Command-/StateInterface in the ``.ros2_control.xacro`` file. + +joint_limits +************ +* Add header to import limits from standard URDF definition (`#1298 `_) + +Adaption of Command-/StateInterfaces +*************************************** +Changes from `(PR #1688) `_ for an overview of related changes and discussion refer to `(PR #1240) `_. + +* ``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 `__). +* The memory for storing the value of a ``Command-/StateInterfaces`` is no longer allocated in the hardware but instead in the ``Command-/StateInterfaces`` itself. +* To access the automatically created ``Command-/StateInterfaces`` we provide the ``std::unordered_map``, 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``. + + +ros2controlcli +************** +* Spawner colours were added to ``list_controllers`` depending upon active or inactive (`#1409 `_) +* The ``set_hardware_component_state`` verb was added (`#1248 `_). Use the following command to set the state of a hardware component + + .. code-block:: bash + + ros2 control set_hardware_component_state + +* The ``load_controller`` now supports parsing of the params file (`#1703 `_). + + .. code-block:: bash + + ros2 control load_controller + +* All the ros2controlcli verbs now support the namespacing through the ROS 2 standard way (`#1703 `_). + + .. code-block:: bash + + ros2 control --ros-args -r __ns:= +>>>>>>> 8cdded3 (Add `PoseSensor` semantic component (#1775)) From e4facc45c1ca29eedb6906be851fb40469e44abd Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Wed, 9 Oct 2024 19:55:16 +0200 Subject: [PATCH 2/2] Fix conflicts --- doc/release_notes.rst | 131 ------------------------------------------ 1 file changed, 131 deletions(-) diff --git a/doc/release_notes.rst b/doc/release_notes.rst index ce72aca386..e709f1141a 100644 --- a/doc/release_notes.rst +++ b/doc/release_notes.rst @@ -6,141 +6,10 @@ This list summarizes the changes between Humble (previous) and Iron (current) re .. note:: -<<<<<<< HEAD This list was created in July 2024, earlier changes may not be included. -======= - .. code-block:: cpp - - #include - ... - RCLCPP_INFO(get_logger(), "controller_manager version: %s", CONTROLLER_MANAGER_VERSION_STR); controller_interface ******************** For details see the controller_manager section. -* Pass URDF to controllers on init (`#1088 `_). -* Pass controller manager update rate on the init of the controller interface (`#1141 `_) -* A method to get node options to setup the controller node #api-breaking (`#1169 `_) -* Export state interfaces from the chainable controller #api-breaking (`#1021 `_) -* All chainable controllers must implement the method ``export_state_interfaces`` to export the state interfaces, similar to ``export_reference_interfaces`` method that is exporting the reference interfaces. -* The controllers will now set ``use_global_arguments`` from `NodeOptions `__ to false, to avoid getting influenced by global arguments (Issue : `#1684 `_) (`#1694 `_). From now on, in order to set the parameters to the controller, the ``--param-file`` option from spawner should be used. -* With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. -* The ``assign_interfaces`` and ``release_interfaces`` methods are now virtual, so that the user can override them to store the interfaces into custom variable types, so that the user can have the flexibility to take the ownership of the loaned interfaces to the controller (`#1743 `_) * The new ``PoseSensor`` semantic component provides a standard interface for hardware providing cartesian poses (`#1775 `_) - -controller_manager -****************** -* URDF is now passed to controllers on init (`#1088 `_) - This should help avoiding extra legwork in controllers to get access to the ``/robot_description``. -* Pass controller manager update rate on the init of the controller interface (`#1141 `_) -* Report inactive controllers as a diagnostics ok instead of an error (`#1184 `_) -* Set chained controller interfaces 'available' for activated controllers (`#1098 `_) - - * Configured chainable controller: Listed exported interfaces are unavailable and unclaimed - * Active chainable controller (not in chained mode): Listed exported interfaces are available but unclaimed - * Active chainable controller (in chained mode): Listed exported interfaces are available and claimed -* Try using SCHED_FIFO on any kernel (`#1142 `_) -* A method to get node options to setup the controller node was added (`#1169 `_): ``get_node_options`` can be overridden by controllers, this would make it easy for other controllers to be able to setup their own custom node options -* CM now subscribes to ``robot_description`` topic instead of ``~/robot_description`` (`#1410 `_). -* Change the controller sorting with an approach similar to directed acyclic graphs (`#1384 `_) -* Changes from `(PR #1256) `__ - - * All ``joints`` defined in the ````-tag have to be present in the URDF received :ref:`by the controller manager `, otherwise the following error is shown: - - The published robot description file (URDF) seems not to be genuine. The following error was caught: not found in URDF. - - This is to ensure that the URDF and the ````-tag are consistent. E.g., for configuration ports use ``gpio`` interface types instead. - - * The syntax for mimic joints is changed to the `official URDF specification `__. - - .. code-block:: xml - - - - - - - - - - - - - - - - - - The parameters within the ``ros2_control`` tag are not supported any more. -* The support for the ``description`` parameter for loading the URDF was removed (`#1358 `_). -* The ``--controller-type`` or ``-t`` spawner arg is removed. Now the controller type is defined in the controller configuration file with ``type`` field (`#1639 `_). -* The ``--namespace`` or ``-n`` spawner arg is deprecated. Now the spawner namespace can be defined using the ROS 2 standard way (`#1640 `_). - -hardware_interface -****************** -* A portable version for string-to-double conversion was added: ``hardware_interface::stod`` (`#1257 `_) -* ``test_components`` was moved to its own package (`#1325 `_) -* The ``ros2_control`` tag now supports parsing of the limits from the URDF into the ``HardwareInfo`` structure. More conservative limits can be defined using the ``min`` and ``max`` attributes per interface (`#1472 `_) - - .. code:: xml - - - - ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware - 2.0 - 3.0 - 2.0 - - - - -1 - 1 - - - - - - - - -* Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 `_) -* Access to logger and clock through ``get_logger`` and ``get_clock`` methods in ResourceManager and HardwareComponents ``Actuator``, ``Sensor`` and ``System`` (`#1585 `_) -* Added ``get_hardware_info`` method to the hardware components interface to access the ``HardwareInfo`` instead of accessing the variable ``info_`` directly (`#1643 `_) -* With (`#1683 `_) the ``rclcpp_lifecycle::State & get_state()`` and ``void set_state(const rclcpp_lifecycle::State & new_state)`` are replaced by ``rclcpp_lifecycle::State & get_lifecycle_state()`` and ``void set_lifecycle_state(const rclcpp_lifecycle::State & new_state)``. This change affects controllers and hardware. This is related to (`#1240 `_) as variant support introduces ``get_state`` and ``set_state`` methods for setting/getting state of handles. -* With (`#1421 `_) a key-value storage is added to InterfaceInfo. This allows to define extra params with per Command-/StateInterface in the ``.ros2_control.xacro`` file. - -joint_limits -************ -* Add header to import limits from standard URDF definition (`#1298 `_) - -Adaption of Command-/StateInterfaces -*************************************** -Changes from `(PR #1688) `_ for an overview of related changes and discussion refer to `(PR #1240) `_. - -* ``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 `__). -* The memory for storing the value of a ``Command-/StateInterfaces`` is no longer allocated in the hardware but instead in the ``Command-/StateInterfaces`` itself. -* To access the automatically created ``Command-/StateInterfaces`` we provide the ``std::unordered_map``, 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``. - - -ros2controlcli -************** -* Spawner colours were added to ``list_controllers`` depending upon active or inactive (`#1409 `_) -* The ``set_hardware_component_state`` verb was added (`#1248 `_). Use the following command to set the state of a hardware component - - .. code-block:: bash - - ros2 control set_hardware_component_state - -* The ``load_controller`` now supports parsing of the params file (`#1703 `_). - - .. code-block:: bash - - ros2 control load_controller - -* All the ros2controlcli verbs now support the namespacing through the ROS 2 standard way (`#1703 `_). - - .. code-block:: bash - - ros2 control --ros-args -r __ns:= ->>>>>>> 8cdded3 (Add `PoseSensor` semantic component (#1775))