Skip to content

Commit 44ece68

Browse files
mateusmenezes95mergify[bot]
authored andcommitted
Move hardware interface README content to sphinx documentation (#1342)
(cherry picked from commit 55eeb09)
1 parent 6f47d8d commit 44ece68

File tree

3 files changed

+173
-129
lines changed

3 files changed

+173
-129
lines changed

hardware_interface/README.md

Lines changed: 3 additions & 129 deletions
Original file line numberDiff line numberDiff line change
@@ -1,131 +1,5 @@
1-
robot agnostic hardware_interface package.
2-
This package will eventually be moved into its own repo.
1+
# Overview
32

4-
## Best practice for `hardware_interface` implementation
5-
In the following section you can find some advices which will help you implement interface
6-
for your specific hardware.
3+
For detailed information about this package, please see the [ros2_control Documentation]!
74

8-
### Best practice for having different update rate for each `hardware_interface` by counting loops
9-
Current implementation of [ros2_control main node](https://github.com/ros-controls/ros2_control/blob/master/controller_manager/src/ros2_control_node.cpp)
10-
has one update rate that controls the rate of the [`read()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L169) and [`write()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L178)
11-
calls in [`hardware_interface(s)`](https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/system_interface.hpp).
12-
In this section suggestion on how to run each interface implementation on its own update rate is introduced.
13-
14-
1. Add parameters of main control loop update rate and desired update rate for your hardware interface.
15-
```
16-
<?xml version="1.0"?>
17-
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
18-
19-
<xacro:macro name="system_interface" params="name main_loop_update_rate desired_hw_update_rate">
20-
21-
<ros2_control name="${name}" type="system">
22-
<hardware>
23-
<plugin>my_system_interface/MySystemHardware</plugin>
24-
<param name="main_loop_update_rate">${main_loop_update_rate}</param>
25-
<param name="desired_hw_update_rate">${desired_hw_update_rate}</param>
26-
</hardware>
27-
...
28-
</ros2_control>
29-
30-
</xacro:macro>
31-
32-
</robot>
33-
```
34-
35-
2. In you [`on_init()`](https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L94) specific implementation fetch desired parameters:
36-
```
37-
namespace my_system_interface
38-
{
39-
hardware_interface::CallbackReturn MySystemHardware::on_init(
40-
const hardware_interface::HardwareInfo & info)
41-
{
42-
if (
43-
hardware_interface::SystemInterface::on_init(info) !=
44-
hardware_interface::CallbackReturn::SUCCESS)
45-
{
46-
return hardware_interface::CallbackReturn::ERROR;
47-
}
48-
49-
// declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ;
50-
main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]);
51-
desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]);
52-
53-
...
54-
}
55-
...
56-
} // my_system_interface
57-
```
58-
59-
3. In your `on_activate()` specific implementation reset internal loop counter
60-
```
61-
hardware_interface::CallbackReturn MySystemHardware::on_activate(
62-
const rclcpp_lifecycle::State & /*previous_state*/)
63-
{
64-
// declaration in *.hpp file --> unsigned int update_loop_counter_ ;
65-
update_loop_counter_ = 0;
66-
...
67-
}
68-
```
69-
70-
4. In your `read(const rclcpp::Time & time, const rclcpp::Duration & period)` and/or
71-
`write(const rclcpp::Time & time, const rclcpp::Duration & period)`
72-
specific implementations decide if you should interfere with your hardware
73-
```
74-
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
75-
{
76-
77-
bool hardware_go = main_loop_update_rate_ == 0 ||
78-
desired_hw_update_rate_ == 0 ||
79-
((update_loop_counter_ % desired_hw_update_rate_) == 0);
80-
81-
if (hardware_go){
82-
// hardware comms and operations
83-
84-
}
85-
...
86-
87-
// update counter
88-
++update_loop_counter_;
89-
update_loop_counter_ %= main_loop_update_rate_;
90-
}
91-
```
92-
93-
### Best practice for having different update rate for each `hardware_interface` by measuring elapsed time
94-
Another way to decide if hardware communication should be executed in the`read(const rclcpp::Time & time, const rclcpp::Duration & period)` and/or
95-
`write(const rclcpp::Time & time, const rclcpp::Duration & period)` implementations is to measure elapsed time since last pass:
96-
97-
```
98-
hardware_interface::CallbackReturn MySystemHardware::on_activate(
99-
const rclcpp_lifecycle::State & /*previous_state*/)
100-
{
101-
// declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ;
102-
first_read_pass_ = first_write_pass_ = true;
103-
...
104-
}
105-
106-
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
107-
{
108-
if (first_read_pass_ || (time - last_read_time_ ) > period)
109-
{
110-
first_read_pass_ = false;
111-
// declaration in *.hpp file --> rclcpp::Time last_read_time_ ;
112-
last_read_time_ = time;
113-
// hardware comms and operations
114-
...
115-
}
116-
...
117-
}
118-
119-
hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period)
120-
{
121-
if (first_write_pass_ || (time - last_write_time_ ) > period)
122-
{
123-
first_write_pass_ = false;
124-
// declaration in *.hpp file --> rclcpp::Time last_write_time_ ;
125-
last_write_time_ = time;
126-
// hardware comms and operations
127-
...
128-
}
129-
...
130-
}
131-
```
5+
[ros2_control Documentation]: https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/hardware_components_userdoc.html
Lines changed: 169 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,169 @@
1+
:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst
2+
3+
.. _different_update_rates_userdoc:
4+
5+
Different update rates for Hardware Components
6+
===============================================================================
7+
8+
In the following sections you can find some advice which will help you to implement Hardware
9+
Components with update rates different from the main control loop.
10+
11+
By counting loops
12+
-------------------------------------------------------------------------------
13+
14+
Current implementation of
15+
`ros2_control main node <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/controller_manager/src/ros2_control_node.cpp>`_
16+
has one update rate that controls the rate of the
17+
`read(...) <https://github.com/ros-controls/ros2_control/blob/0bdcd414c7ab8091f3e1b8d9b73a91c778388e82/hardware_interface/include/hardware_interface/system_interface.hpp#L175>`_
18+
and `write(...) <https://github.com/ros-controls/ros2_control/blob/fe462926416d527d1da163bc3eabd02ee1de9be9/hardware_interface/include/hardware_interface/system_interface.hpp#L178>`_
19+
calls in `hardware_interface(s) <https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/include/hardware_interface/system_interface.hpp>`_.
20+
To achieve different update rates for your hardware component you can use the following steps:
21+
22+
.. _step-1:
23+
24+
1. Add parameters of main control loop update rate and desired update rate for your hardware component
25+
26+
.. code:: xml
27+
28+
<?xml version="1.0"?>
29+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
30+
31+
<xacro:macro name="system_interface" params="name main_loop_update_rate desired_hw_update_rate">
32+
33+
<ros2_control name="${name}" type="system">
34+
<hardware>
35+
<plugin>my_system_interface/MySystemHardware</plugin>
36+
<param name="main_loop_update_rate">${main_loop_update_rate}</param>
37+
<param name="desired_hw_update_rate">${desired_hw_update_rate}</param>
38+
</hardware>
39+
...
40+
</ros2_control>
41+
42+
</xacro:macro>
43+
44+
</robot>
45+
46+
.. _step-2:
47+
48+
2. In you ``on_init()`` specific implementation fetch the desired parameters
49+
50+
.. code:: cpp
51+
52+
namespace my_system_interface
53+
{
54+
hardware_interface::CallbackReturn MySystemHardware::on_init(
55+
const hardware_interface::HardwareInfo & info)
56+
{
57+
if (
58+
hardware_interface::SystemInterface::on_init(info) !=
59+
hardware_interface::CallbackReturn::SUCCESS)
60+
{
61+
return hardware_interface::CallbackReturn::ERROR;
62+
}
63+
64+
// declaration in *.hpp file --> unsigned int main_loop_update_rate_, desired_hw_update_rate_ = 100 ;
65+
main_loop_update_rate_ = stoi(info_.hardware_parameters["main_loop_update_rate"]);
66+
desired_hw_update_rate_ = stoi(info_.hardware_parameters["desired_hw_update_rate"]);
67+
68+
...
69+
}
70+
...
71+
} // my_system_interface
72+
73+
3. In your ``on_activate`` specific implementation reset internal loop counter
74+
75+
.. code:: cpp
76+
77+
hardware_interface::CallbackReturn MySystemHardware::on_activate(
78+
const rclcpp_lifecycle::State & /*previous_state*/)
79+
{
80+
// declaration in *.hpp file --> unsigned int update_loop_counter_ ;
81+
update_loop_counter_ = 0;
82+
...
83+
}
84+
85+
4. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)``
86+
and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
87+
specific implementations decide if you should interfere with your hardware
88+
89+
.. code:: cpp
90+
91+
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
92+
{
93+
94+
bool hardware_go = main_loop_update_rate_ == 0 ||
95+
desired_hw_update_rate_ == 0 ||
96+
((update_loop_counter_ % desired_hw_update_rate_) == 0);
97+
98+
if (hardware_go){
99+
// hardware comms and operations
100+
...
101+
}
102+
...
103+
104+
// update counter
105+
++update_loop_counter_;
106+
update_loop_counter_ %= main_loop_update_rate_;
107+
}
108+
109+
By measuring elapsed time
110+
-------------------------------------------------------------------------------
111+
112+
Another way to decide if hardware communication should be executed in the
113+
``read(const rclcpp::Time & time, const rclcpp::Duration & period)`` and/or
114+
``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
115+
implementations is to measure elapsed time since last pass:
116+
117+
1. In your ``on_activate`` specific implementation reset the flags that indicate
118+
that this is the first pass of the ``read`` and ``write`` methods
119+
120+
.. code:: cpp
121+
122+
hardware_interface::CallbackReturn MySystemHardware::on_activate(
123+
const rclcpp_lifecycle::State & /*previous_state*/)
124+
{
125+
// declaration in *.hpp file --> bool first_read_pass_, first_write_pass_ = true ;
126+
first_read_pass_ = first_write_pass_ = true;
127+
...
128+
}
129+
130+
2. In your ``read(const rclcpp::Time & time, const rclcpp::Duration & period)``
131+
and/or ``write(const rclcpp::Time & time, const rclcpp::Duration & period)``
132+
specific implementations decide if you should interfere with your hardware
133+
134+
.. code:: cpp
135+
136+
hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period)
137+
{
138+
if (first_read_pass_ || (time - last_read_time_ ) > desired_hw_update_period_)
139+
{
140+
first_read_pass_ = false;
141+
// declaration in *.hpp file --> rclcpp::Time last_read_time_ ;
142+
last_read_time_ = time;
143+
// hardware comms and operations
144+
...
145+
}
146+
...
147+
}
148+
149+
hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period)
150+
{
151+
if (first_write_pass_ || (time - last_write_time_ ) > desired_hw_update_period_)
152+
{
153+
first_write_pass_ = false;
154+
// declaration in *.hpp file --> rclcpp::Time last_write_time_ ;
155+
last_write_time_ = time;
156+
// hardware comms and operations
157+
...
158+
}
159+
...
160+
}
161+
162+
.. note::
163+
164+
The approach to get the desired update period value from the URDF and assign it to the variable
165+
``desired_hw_update_period_`` is the same as in the previous section (|step-1|_ and |step-2|_) but
166+
with a different parameter name.
167+
168+
.. |step-1| replace:: step 1
169+
.. |step-2| replace:: step 2

hardware_interface/doc/hardware_components_userdoc.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ Guidelines and Best Practices
1616

1717
Hardware Interface Types <hardware_interface_types_userdoc.rst>
1818
Writing a Hardware Component <writing_new_hardware_component.rst>
19+
Different Update Rates <different_update_rates_userdoc.rst>
1920

2021

2122
Handling of errors that happen during read() and write() calls

0 commit comments

Comments
 (0)