Skip to content

Commit

Permalink
Update documentation and the release notes
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jun 17, 2024
1 parent 0c5e78d commit 3e31fb4
Show file tree
Hide file tree
Showing 2 changed files with 118 additions and 160 deletions.
37 changes: 37 additions & 0 deletions doc/release_notes/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,43 @@ hardware_interface
</ros2_control>
* Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 <https://github.com/ros-controls/ros2_control/pull/1488>`_)
* The ``ros2_control`` tag now supports parsing read/write rate ``rw_rate`` for the each hardware component parsed through the URDF (`#1570 <https://github.com/ros-controls/ros2_control/pull/1570>`_)

.. code:: xml
<ros2_control name="RRBotSystemMutipleGPIOs" type="system" rw_rate="500">
<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"/>
<command_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="joint2">
<command_interface name="position"/>
<state_interface name="position"/>
</joint>
</ros2_control>
<ros2_control name="MultimodalGripper" type="actuator" rw_rate="200">
<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>
<gpio name="suction">
<command_interface name="suction"/>
<state_interface name="suction"/>
</gpio>
</ros2_control>
joint_limits
************
Expand Down
241 changes: 81 additions & 160 deletions hardware_interface/doc/different_update_rates_userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -5,165 +5,86 @@
Different update rates for Hardware Components
===============================================================================

In the following sections you can find some advice which will help you to implement Hardware
Components with update rates different from the main control loop.

By counting loops
-------------------------------------------------------------------------------

Current implementation of
`ros2_control main node <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/controller_manager/src/ros2_control_node.cpp>`_
has one update rate that controls the rate of the
`read(...) <https://github.com/ros-controls/ros2_control/blob/0bdcd414c7ab8091f3e1b8d9b73a91c778388e82/hardware_interface/include/hardware_interface/system_interface.hpp#L175>`_
and `write(...) <https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L178>`_
calls in `hardware_interface(s) <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/system_interface.hpp>`_.
To achieve different update rates for your hardware component you can use the following steps:

.. _step-1:

1. Add parameters of main control loop update rate and desired update rate for your hardware component

.. code:: xml
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="system_interface" params="name main_loop_update_rate desired_hw_update_rate">
<ros2_control name="${name}" type="system">
<hardware>
<plugin>my_system_interface/MySystemHardware</plugin>
<param name="main_loop_update_rate">${main_loop_update_rate}</param>
<param name="desired_hw_update_rate">${desired_hw_update_rate}</param>
</hardware>
...
</ros2_control>
</xacro:macro>
</robot>
.. _step-2:

2. In you ``on_init()`` specific implementation fetch the desired parameters

.. code:: cpp
namespace my_system_interface
{
hardware_interface::CallbackReturn MySystemHardware::on_init(
const hardware_interface::HardwareInfo & info)
{
if (
hardware_interface::SystemInterface::on_init(info) !=
hardware_interface::CallbackReturn::SUCCESS)
{
return hardware_interface::CallbackReturn::ERROR;
}
// declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ;
main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]);
desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]);
...
}
...
} // my_system_interface
3. In your ``on_activate`` specific implementation reset internal loop counter

.. code:: cpp
hardware_interface::CallbackReturn MySystemHardware::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
// declaration in *.hpp file --> unsigned int update_loop_counter_ ;
update_loop_counter_ = 0;
...
}
4. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)``
and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
specific implementations decide if you should interfere with your hardware

.. code:: cpp
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
{
bool hardware_go = main_loop_update_rate_ == 0 ||
desired_hw_update_rate_ == 0 ||
((update_loop_counter_ % desired_hw_update_rate_) == 0);
if (hardware_go){
// hardware comms and operations
...
}
...
// update counter
++update_loop_counter_;
update_loop_counter_ %= main_loop_update_rate_;
}
By measuring elapsed time
-------------------------------------------------------------------------------

Another way to decide if hardware communication should be executed in the
``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` and/or
``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
implementations is to measure elapsed time since last pass:

1. In your ``on_activate`` specific implementation reset the flags that indicate
that this is the first pass of the ``read`` and ``write`` methods

.. code:: cpp
hardware_interface::CallbackReturn MySystemHardware::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
// declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ;
first_read_pass_ = first_write_pass_ = true;
...
}
2. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)``
and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
specific implementations decide if you should interfere with your hardware

.. code:: cpp
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (first_read_pass_ || (time - last_read_time_ ) > desired_hw_update_period_)
{
first_read_pass_ = false;
// declaration in *.hpp file --> rclcpp::Time last_read_time_ ;
last_read_time_ = time;
// hardware comms and operations
...
}
...
}
hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period)
{
if (first_write_pass_ || (time - last_write_time_ ) > desired_hw_update_period_)
{
first_write_pass_ = false;
// declaration in *.hpp file --> rclcpp::Time last_write_time_ ;
last_write_time_ = time;
// hardware comms and operations
...
}
...
}
The ``ros2_control`` framework allows to run different hardware components at different update rates. This is useful when some of the hardware components needs to run at a different frequency than the traditional control loop frequency which is same as the one of the ``controller_manager``. It is very typical to have different components with different frequencies in a robotic system with different sensors or different components using different communication protocols.
This is useful when you have a hardware component that needs to run at a higher rate than the rest of the components. For example, you might have a sensor that needs to be read at 1000Hz, while the rest of the components can run at 500Hz, given that the control loop frequency of the ``controller_manager`` is higher than 1000Hz. The read/write rate can be defined easily by adding the parameter ``rw_rate`` to the ``ros2_control`` tag of the hardware component.

Examples
*****************************
The following examples show how to use the different hardware interface types with different update frequencies in a ``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 running at different rates:

.. code-block:: xml
<ros2_control name="RRBotSystemMutipleGPIOs" type="system" rw_rate="500">
<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" rw_rate="200">
<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>
<gpio name="suction">
<command_interface name="suction"/>
<state_interface name="suction"/> <!-- Needed to know current state of the output -->
</gpio>
</ros2_control>
<ros2_control name="RRBotForceTorqueSensor2D" type="sensor" rw_rate="250">
<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 system hardware component that controls the joints of the RRBot is running at 500 Hz, the multimodal gripper is running at 200 Hz and the force torque sensor is running at 250 Hz.

.. note::

The approach to get the desired update period value from the URDF and assign it to the variable
``desired_hw_update_period_`` is the same as in the previous section (|step-1|_ and |step-2|_) but
with a different parameter name.

.. |step-1| replace:: step 1
.. |step-2| replace:: step 2
In the above example, the ``rw_rate`` parameter is set to 500 Hz, 200 Hz and 250 Hz for the system, actuator and sensor hardware components respectively. This parameter is optional and if not set, the default value of 0 will be used which means that the hardware component will run at the same rate as the ``controller_manager``. However, if the specified rate is higher than the ``controller_manager`` rate, the hardware component will then run at the rate of the ``controller_manager``.

0 comments on commit 3e31fb4

Please sign in to comment.