ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Async hardware reads in system interface (ros2_controls)

asked 2021-02-15 18:02:22 -0500

guru_florida gravatar image

I'm porting my hardware interfaces to the new ros2_controls hardware system interface. We are to implement the read() and write() method overrides. However, we often don't have a low latency connection to our joints so how should we handle reads without blocking the main controller manager executor thread? Here are some possibilities I am thinking about:

The bus is a low-latency (bot not insignificant) serial connection with about 2ms round trip.

  1. Simple. Block read in the read() method.
  2. Initiate async query command on the bus immediately after the command write in the write() method. Expect the data may be available during the next read() call.
  3. Create a new executor thread (or pthread) and implement our own control loop for both state and commands. The overridden read() and write() methods are then only updating class variables.

What is recommended here? I don't like 1. Two depends on internal implementation and I cant control the timing between read()/write() even though my hardware timing is pretty well known. Seems like 3 is the best way, and I probably should implement a realtime barrier as well.

Thanks ahead for your time and consideration.

Colin

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-02-16 04:45:39 -0500

updated 2021-02-16 04:47:37 -0500

Hi,

Thanks for your question. In the past, I addressed this issue using 3. approach. It provides you with most flexibility to control execution behavior. I implemented this approach for Force-Torque Sensors in ROS1 where the sensors are running at 800 Hz and the control loop at 200 Hz (because of robot). The problem with FTS is other way around, but the solution is the same. I don't guarantee that this implementation is real-time safe, but it can give you an idea about the architecture.

Nevertheless, you probably don't want to run your CM at faster rate than you can talk to your HW.

Maybe you would like to start with a minimal example? If so, RRbot from the ros2_control_demos package would be perfect to test the concept, especially when using an additional executor or internal thread.

For the real-time barrier, RealtimeBuffer from realtime_tools repo could be helpful.

edit flag offensive delete link more

Comments

1

Option 3 it is. I saw the RealtimeBuffer's use in control_toolbox's PID implementation and I was thinking the same. Thank you!

guru_florida gravatar image guru_florida  ( 2021-02-16 11:59:19 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-02-15 18:02:22 -0500

Seen: 485 times

Last updated: Feb 16 '21