From 6a0995e80ee81209167da2dde73eb10781513dd8 Mon Sep 17 00:00:00 2001 From: Mateus Menezes Date: Sat, 27 Jan 2024 19:51:56 -0300 Subject: [PATCH 1/3] Move hardware component md doc to sphinx doc --- hardware_interface/README.md | 132 +-------------- .../doc/different_update_rates_userdoc.rst | 156 ++++++++++++++++++ .../doc/hardware_components_userdoc.rst | 1 + 3 files changed, 160 insertions(+), 129 deletions(-) create mode 100644 hardware_interface/doc/different_update_rates_userdoc.rst diff --git a/hardware_interface/README.md b/hardware_interface/README.md index 343158b698..58c77b8467 100644 --- a/hardware_interface/README.md +++ b/hardware_interface/README.md @@ -1,131 +1,5 @@ -robot agnostic hardware_interface package. -This package will eventually be moved into its own repo. +# Overview -## Best practice for `hardware_interface` implementation -In the following section you can find some advices which will help you implement interface -for your specific hardware. +Robot agnostic hardware_interface package. This package will eventually be moved into its own repo. For detailed information about this package, please see the [ros2_control Documentation]! -### Best practice for having different update rate for each `hardware_interface` by counting loops -Current implementation of [ros2_control main node](https://github.com/ros-controls/ros2_control/blob/master/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/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) -calls in [`hardware_interface(s)`](https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/system_interface.hpp). -In this section suggestion on how to run each interface implementation on its own update rate is introduced. - -1. Add parameters of main control loop update rate and desired update rate for your hardware interface. -``` - - - - - - - - my_system_interface/MySystemHardware - ${main_loop_update_rate} - ${desired_hw_update_rate} - - ... - - - - - -``` - -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: -``` -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 -``` -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 -``` -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_; -} -``` - -### Best practice for having different update rate for each `hardware_interface` 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: - -``` -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; - ... -} - -hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) -{ - if (first_read_pass_ || (time - last_read_time_ ) > 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_ ) > period) - { - first_write_pass_ = false; - // declaration in *.hpp file --> rclcpp::Time last_write_time_ ; - last_write_time_ = time; - // hardware comms and operations - ... - } - ... -} -``` +[ros2_control Documentation]: https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/hardware_components_userdoc.html diff --git a/hardware_interface/doc/different_update_rates_userdoc.rst b/hardware_interface/doc/different_update_rates_userdoc.rst new file mode 100644 index 0000000000..822c326304 --- /dev/null +++ b/hardware_interface/doc/different_update_rates_userdoc.rst @@ -0,0 +1,156 @@ +:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/hardware_interface/doc/different_update_rates_userdoc.rst + +.. _different_update_rates_userdoc: + +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 `_ +has one update rate that controls the rate of the +`read(...) `_ +and `write(...) `_ +calls in `hardware_interface(s) `_. +To achieve different update rates for your hardware component you can use the following steps: + +1. Add parameters of main control loop update rate and desired update rate for your hardware component + + .. code:: xml + + + + + + + + + my_system_interface/MySystemHardware + ${main_loop_update_rate} + ${desired_hw_update_rate} + + ... + + + + + + +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_ ) > 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_ ) > period) + { + first_write_pass_ = false; + // declaration in *.hpp file --> rclcpp::Time last_write_time_ ; + last_write_time_ = time; + // hardware comms and operations + ... + } + ... + } diff --git a/hardware_interface/doc/hardware_components_userdoc.rst b/hardware_interface/doc/hardware_components_userdoc.rst index 1a8c5e611b..404e90ee03 100644 --- a/hardware_interface/doc/hardware_components_userdoc.rst +++ b/hardware_interface/doc/hardware_components_userdoc.rst @@ -16,6 +16,7 @@ Guidelines and Best Practices Hardware Interface Types Writing a Hardware Component + Different Update Rates Handling of errors that happen during read() and write() calls From 518856cd7130809a112d54b9b524e4b251a60564 Mon Sep 17 00:00:00 2001 From: "Dr. Denis" Date: Thu, 1 Feb 2024 19:45:23 +0100 Subject: [PATCH 2/3] Correct false assumption. --- hardware_interface/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/hardware_interface/README.md b/hardware_interface/README.md index 58c77b8467..76480201cb 100644 --- a/hardware_interface/README.md +++ b/hardware_interface/README.md @@ -1,5 +1,5 @@ # Overview -Robot agnostic hardware_interface package. This package will eventually be moved into its own repo. For detailed information about this package, please see the [ros2_control Documentation]! +For detailed information about this package, please see the [ros2_control Documentation]! [ros2_control Documentation]: https://control.ros.org/master/doc/ros2_control/hardware_interface/doc/hardware_components_userdoc.html From 00c63b41544bd383540790695abdf8fed6a6482b Mon Sep 17 00:00:00 2001 From: Mateus Menezes Date: Thu, 1 Feb 2024 20:50:59 -0300 Subject: [PATCH 3/3] Change code snippet of "By measuring elapsed time section" --- .../doc/different_update_rates_userdoc.rst | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/hardware_interface/doc/different_update_rates_userdoc.rst b/hardware_interface/doc/different_update_rates_userdoc.rst index 822c326304..23f5e3564a 100644 --- a/hardware_interface/doc/different_update_rates_userdoc.rst +++ b/hardware_interface/doc/different_update_rates_userdoc.rst @@ -19,6 +19,8 @@ and `write(...) `_. 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 @@ -41,6 +43,8 @@ To achieve different update rates for your hardware component you can use the fo +.. _step-2: + 2. In you ``on_init()`` specific implementation fetch the desired parameters .. code:: cpp @@ -131,7 +135,7 @@ implementations is to measure elapsed time since last pass: hardware_interface::return_type MySystemHardware::read(const rclcpp::Time & time, const rclcpp::Duration & period) { - if (first_read_pass_ || (time - last_read_time_ ) > 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_ ; @@ -144,7 +148,7 @@ implementations is to measure elapsed time since last pass: hardware_interface::return_type MySystemHardware::write(const rclcpp::Time & time, const rclcpp::Duration & period) { - if (first_write_pass_ || (time - last_write_time_ ) > 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_ ; @@ -154,3 +158,12 @@ implementations is to measure elapsed time since last pass: } ... } + +.. 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