Skip to content

Commit

Permalink
Merge branch 'master' into fix/spawner/on/resource/conflict
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 21, 2024
2 parents b436a4e + a86b534 commit 1ce28ff
Show file tree
Hide file tree
Showing 36 changed files with 286 additions and 32 deletions.
2 changes: 1 addition & 1 deletion .github/ISSUE_TEMPLATE/good-first-issue.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
name: Good first issue
about: Create an issue to welcome a new contributor into the community.
title: ''
labels: good-first-issue
labels: ["good first issue"]
assignees: ''

---
Expand Down
6 changes: 6 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.22.0 (2024-12-20)
-------------------
* Fixed typo. Added s to state_interfaces\_ (`#1930 <https://github.com/ros-controls/ros2_control/issues/1930>`_)
* [CI] Add clang job, setup concurrency, use rt_tools humble branch (`#1910 <https://github.com/ros-controls/ros2_control/issues/1910>`_)
* Contributors: Christoph Fröhlich, louietouie

4.21.0 (2024-12-06)
-------------------
* [Diagnostics] Add diagnostics of execution time and periodicity of the controllers and controller_manager (`#1871 <https://github.com/ros-controls/ros2_control/issues/1871>`_)
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>4.21.0</version>
<version>4.22.0</version>
<description>Description of controller_interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
13 changes: 13 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,19 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.22.0 (2024-12-20)
-------------------
* Async Hardware Components (`#1567 <https://github.com/ros-controls/ros2_control/issues/1567>`_)
* Add controller node options args to be able to set controller specific node arguments (`#1713 <https://github.com/ros-controls/ros2_control/issues/1713>`_)
* Use singleton approach to store and reuse the service clients (`#1949 <https://github.com/ros-controls/ros2_control/issues/1949>`_)
* Increase the max and min periodicity tolerances to fix flaky tests (`#1937 <https://github.com/ros-controls/ros2_control/issues/1937>`_)
* Fix the spawner to support full wildcard parameter entries (`#1933 <https://github.com/ros-controls/ros2_control/issues/1933>`_)
* Suppress unnecessary warnings in clock received validation (`#1935 <https://github.com/ros-controls/ros2_control/issues/1935>`_)
* Optimize the valid time check in the update loop (`#1923 <https://github.com/ros-controls/ros2_control/issues/1923>`_)
* [CI] Add clang job, setup concurrency, use rt_tools humble branch (`#1910 <https://github.com/ros-controls/ros2_control/issues/1910>`_)
* Update CPU affinity parameter to be able to set multiple CPUs (`#1915 <https://github.com/ros-controls/ros2_control/issues/1915>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota, Takashi Sato

4.21.0 (2024-12-06)
-------------------
* Use the .hpp headers from realtime_tools package (`#1916 <https://github.com/ros-controls/ros2_control/issues/1916>`_)
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>4.21.0</version>
<version>4.22.0</version>
<description>Description of controller_manager</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.22.0 (2024-12-20)
-------------------

4.21.0 (2024-12-06)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>4.21.0</version>
<version>4.22.0</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
10 changes: 10 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

4.22.0 (2024-12-20)
-------------------
* Propagate read/write rate to the HardwareInfo properly (`#1928 <https://github.com/ros-controls/ros2_control/issues/1928>`_)
* Async Hardware Components (`#1567 <https://github.com/ros-controls/ros2_control/issues/1567>`_)
* Add controller node options args to be able to set controller specific node arguments (`#1713 <https://github.com/ros-controls/ros2_control/issues/1713>`_)
* Make get_name() return a const reference (`#1952 <https://github.com/ros-controls/ros2_control/issues/1952>`_)
* Let sensors also export state interfaces of joints (`#1885 <https://github.com/ros-controls/ros2_control/issues/1885>`_)
* [CI] Add clang job, setup concurrency, use rt_tools humble branch (`#1910 <https://github.com/ros-controls/ros2_control/issues/1910>`_)
* Contributors: Christoph Fröhlich, Sai Kishor Kothakota, Takashi Sato

4.21.0 (2024-12-06)
-------------------
* [Feature] Choose different read and write rate for the hardware components (`#1570 <https://github.com/ros-controls/ros2_control/issues/1570>`_)
Expand Down
99 changes: 99 additions & 0 deletions hardware_interface/doc/asynchronous_components.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst

.. _asynchronous_components:

Running Hardware Components Asynchronously
============================================

The ``ros2_control`` framework allows to run hardware components asynchronously. This is useful when some of the hardware components need to run in a separate thread or executor. For example, a sensor takes longer to read data that affects the periodicity of the ``controller_manager`` control loop. In this case, the sensor can be run in a separate thread or executor to avoid blocking the control loop.

Parameters
-----------

The following parameters can be set in the ``ros2_control`` hardware configuration to run the hardware component asynchronously:

* ``is_async``: (optional) If set to ``true``, the hardware component will run asynchronously. Default is ``false``.
* ``thread_priority``: (optional) The priority of the thread that runs the hardware component. The priority is an integer value between 0 and 99. The default value is 50.

.. note::
The thread priority is only used when the hardware component is run asynchronously.
When the hardware component is run asynchronously, it uses the FIFO scheduling policy.

Examples
---------

The following examples show how to use the different hardware interface types synchronously and asynchronously with ``ros2_control`` URDF.
They can be combined together within the different hardware component types (system, actuator, sensor) (:ref:`see detailed documentation <overview_hardware_components>`) as follows

For a RRBot with multimodal gripper and external sensor:

.. code-block:: xml
<ros2_control name="RRBotSystemMutipleGPIOs" type="system">
<hardware>
<plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
<param name="example_param_hw_start_duration_sec">2.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">2.0</param>
</hardware>
<joint name="joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<gpio name="flange_digital_IOs">
<command_interface name="digital_output1"/>
<state_interface name="digital_output1"/> <!-- Needed to know current state of the output -->
<command_interface name="digital_output2"/>
<state_interface name="digital_output2"/>
<state_interface name="digital_input1"/>
<state_interface name="digital_input2"/>
</gpio>
</ros2_control>
<ros2_control name="MultimodalGripper" type="actuator" is_async="true" thread_priority="30">
<hardware>
<plugin>ros2_control_demo_hardware/MultimodalGripper</plugin>
</hardware>
<joint name="parallel_fingers">
<command_interface name="position">
<param name="min">0</param>
<param name="max">100</param>
</command_interface>
<state_interface name="position"/>
</joint>
</ros2_control>
<ros2_control name="RRBotForceTorqueSensor2D" type="sensor" is_async="true">
<hardware>
<plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
<param name="example_param_read_for_sec">0.43</param>
</hardware>
<sensor name="tcp_fts_sensor">
<state_interface name="fx"/>
<state_interface name="tz"/>
<param name="frame_id">kuka_tcp</param>
<param name="fx_range">100</param>
<param name="tz_range">100</param>
</sensor>
<sensor name="temp_feedback">
<state_interface name="temperature"/>
</sensor>
<gpio name="calibration">
<command_interface name="calibration_matrix_nr"/>
<state_interface name="calibration_matrix_nr"/>
</gpio>
</ros2_control>
In the above example, the following components are defined:

* A system hardware component named ``RRBotSystemMutipleGPIOs`` with two joints and a GPIO component that runs synchronously.
* An actuator hardware component named ``MultimodalGripper`` with a joint that runs asynchronously with a thread priority of 30.
* A sensor hardware component named ``RRBotForceTorqueSensor2D`` with two sensors and a GPIO component that runs asynchronously with the default thread priority of 50.
1 change: 1 addition & 0 deletions hardware_interface/doc/hardware_components_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ Guidelines and Best Practices
Hardware Interface Types <hardware_interface_types_userdoc.rst>
Writing a Hardware Component <writing_new_hardware_component.rst>
Different Update Rates <different_update_rates_userdoc.rst>
Asynchronous Execution <asynchronous_components.rst>


Handling of errors that happen during read() and write() calls
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "hardware_interface/types/trigger_type.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/logger.hpp"
Expand Down Expand Up @@ -546,11 +547,6 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
// interface names to Handle accessed through getters/setters
std::unordered_map<std::string, StateInterface::SharedPtr> actuator_states_;
std::unordered_map<std::string, CommandInterface::SharedPtr> actuator_commands_;
enum class TriggerType
{
READ,
WRITE
};
std::atomic<TriggerType> next_trigger_ = TriggerType::READ;
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/types/hardware_interface_type_values.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "hardware_interface/types/trigger_type.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/logger.hpp"
Expand Down Expand Up @@ -585,11 +586,6 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
// interface names to Handle accessed through getters/setters
std::unordered_map<std::string, StateInterface::SharedPtr> system_states_;
std::unordered_map<std::string, CommandInterface::SharedPtr> system_commands_;
enum class TriggerType
{
READ,
WRITE
};
std::atomic<TriggerType> next_trigger_ = TriggerType::READ;
};

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright 2024 ros2_control Development Team
//
// 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 HARDWARE_INTERFACE__TYPES__TRIGGER_TYPE_HPP_
#define HARDWARE_INTERFACE__TYPES__TRIGGER_TYPE_HPP_

namespace hardware_interface
{
enum class TriggerType
{
READ,
WRITE
};

} // namespace hardware_interface

#endif // HARDWARE_INTERFACE__TYPES__TRIGGER_TYPE_HPP_
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface</name>
<version>4.21.0</version>
<version>4.22.0</version>
<description>ros2_control hardware interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
12 changes: 7 additions & 5 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,10 +141,7 @@ class ResourceStorage
component_info.name = hardware_info.name;
component_info.type = hardware_info.type;
component_info.group = hardware_info.group;
component_info.rw_rate =
(hardware_info.rw_rate == 0 || hardware_info.rw_rate > cm_update_rate_)
? cm_update_rate_
: hardware_info.rw_rate;
component_info.rw_rate = hardware_info.rw_rate;
component_info.plugin_name = hardware_info.hardware_plugin_name;
component_info.is_async = hardware_info.is_async;

Expand Down Expand Up @@ -1051,7 +1048,12 @@ bool ResourceManager::load_and_initialize_components(

resource_storage_->cm_update_rate_ = update_rate;

const auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
auto hardware_info = hardware_interface::parse_control_resources_from_urdf(urdf);
// Set the update rate for all hardware components
for (auto & hw : hardware_info)
{
hw.rw_rate = (hw.rw_rate == 0 || hw.rw_rate > update_rate) ? update_rate : hw.rw_rate;
}

const std::string system_type = "system";
const std::string sensor_type = "sensor";
Expand Down
14 changes: 11 additions & 3 deletions hardware_interface/test/mock_components/test_generic_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -699,9 +699,11 @@ class TestableResourceManager : public hardware_interface::ResourceManager
}

explicit TestableResourceManager(
rclcpp::Node & node, const std::string & urdf, bool activate_all = false)
rclcpp::Node & node, const std::string & urdf, bool activate_all = false,
unsigned int cm_update_rate = 100)
: hardware_interface::ResourceManager(
urdf, node.get_node_clock_interface(), node.get_node_logging_interface(), activate_all, 100)
urdf, node.get_node_clock_interface(), node.get_node_logging_interface(), activate_all,
cm_update_rate)
{
}
};
Expand Down Expand Up @@ -842,14 +844,17 @@ void generic_system_functional_test(
EXPECT_EQ(
status_map[component_name].state.label(),
hardware_interface::lifecycle_state_names::UNCONFIGURED);
EXPECT_EQ(status_map[component_name].rw_rate, 100u);
configure_components(rm, {component_name});
status_map = rm.get_components_status();
EXPECT_EQ(
status_map[component_name].state.label(), hardware_interface::lifecycle_state_names::INACTIVE);
EXPECT_EQ(status_map[component_name].rw_rate, 100u);
activate_components(rm, {component_name});
status_map = rm.get_components_status();
EXPECT_EQ(
status_map[component_name].state.label(), hardware_interface::lifecycle_state_names::ACTIVE);
EXPECT_EQ(status_map[component_name].rw_rate, 100u);

// Check initial values
hardware_interface::LoanedStateInterface j1p_s = rm.claim_state_interface("joint1/position");
Expand Down Expand Up @@ -935,7 +940,7 @@ void generic_system_error_group_test(
const std::string & urdf, const std::string component_prefix, bool validate_same_group)
{
rclcpp::Node node("test_generic_system");
TestableResourceManager rm(node, urdf);
TestableResourceManager rm(node, urdf, false, 200u);
const std::string component1 = component_prefix + "1";
const std::string component2 = component_prefix + "2";
// check is hardware is configured
Expand All @@ -944,14 +949,17 @@ void generic_system_error_group_test(
{
EXPECT_EQ(
status_map[component].state.label(), hardware_interface::lifecycle_state_names::UNCONFIGURED);
EXPECT_EQ(status_map[component].rw_rate, 200u);
configure_components(rm, {component});
status_map = rm.get_components_status();
EXPECT_EQ(
status_map[component].state.label(), hardware_interface::lifecycle_state_names::INACTIVE);
EXPECT_EQ(status_map[component].rw_rate, 200u);
activate_components(rm, {component});
status_map = rm.get_components_status();
EXPECT_EQ(
status_map[component].state.label(), hardware_interface::lifecycle_state_names::ACTIVE);
EXPECT_EQ(status_map[component].rw_rate, 200u);
}

// Check initial values
Expand Down
Loading

0 comments on commit 1ce28ff

Please sign in to comment.