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

Which ways of communicating with a controller are real-time safe?

asked 2011-03-15 00:54:26 -0500

bit-pirate gravatar image

Hi there!

I'm developing a custom controller, which in the end should run in a real-time environment. Hence, I would like to ensure, that what I develop is real-time safe. More specific, I would like to know, which possibilities there are to communicate with a controller from outside of the real-time environment. For my use case, the communication itself has not to be real-time safe, but it should not make the controller go out of real-time.

I would be very happy, if somebody could provide better insight into that topic!

Let's start with what I found out up till now. During my work, I saw a couple of possible ways for communication, namely subscribers/publishers, service calls and "normal" (set-)functions providing the ability to change class members of the controller.

Which of them run "where" in terms of "in real-time" or "in non real-time"? One example: In the tutorials there are service calls (realtime_joint_controller) and normal set-functions (JointVelocityController, source code) used to changed the values of class members . Are both ways real-time safe and if so, why? Another example: I read about the special variant of the ROS publisher, which is real-time safe (realtime_tools). Does the description in the package summary imply, that a normal ROS subscriber is not real-time safe?

Let me add, that I am no real-time expert. So, I would appreciate simple explanations! :-)

Thanks a lot for your help!

:-) Marcus

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
8

answered 2011-03-22 14:09:27 -0500

sglaser gravatar image

updated 2011-03-25 10:38:42 -0500

Hi Marcus,

The update(), starting(), and stopping() calls of your controller are the only methods which execute in the realtime thread. Everything else (including init() and any ROS callbacks) executes in a different, concurrent, non-realtime thread.

Normal ROS publishers are absolutely NOT realtime safe. The RealtimePublisher in realtime_tools is realtime safe.

Edit: forgot that starting() and stopping() both run in realtime.

edit flag offensive delete link more

Comments

"[...] any ROS callbacks) [...]" i guess that includes subscribers and services as well?
bit-pirate gravatar image bit-pirate  ( 2011-03-25 04:25:21 -0500 )edit
Subscribers, services, timers, parameter updates. All of these run in non-realtime. Only `update()`, `starting()`, and `stopping()` run in realtime.
sglaser gravatar image sglaser  ( 2011-03-25 10:39:30 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2011-03-15 00:54:26 -0500

Seen: 1,549 times

Last updated: Mar 25 '11