Skip to content

Files

Latest commit

Aug 17, 2023
33e77b8 · Aug 17, 2023

History

History
This branch is 425 commits behind ros-controls/ros2_control:master.

hardware_interface

Folders and files

NameName
Last commit message
Last commit date

parent directory

..
Jun 7, 2023
Jun 23, 2023
Jul 18, 2023
Jun 21, 2023
Aug 17, 2023
Jun 21, 2023
Jul 5, 2022
Feb 22, 2021
Jul 5, 2022
Aug 17, 2023

robot agnostic hardware_interface package. This package will eventually be moved into its own repo.

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.

Best practice for having different update rate for each hardware_interface 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). 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.
<?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>
  1. In you on_init() 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
  1. 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;
    ...
}
  1. 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 theread(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
      ...
    }
    ...
}