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

Revision history [back]

click to hide/show revision 1
initial version

The doc for ros_control says controller_manager provides a hard RT loop.

knowing that ROS is designed for non-RT OS (plain linux), how is that possible on a non-RT OS?

It isn't. Not without making Linux capable of some deterministic scheduling and execution.

Two well known ways to add deterministic scheduling to a Linux system are to patch the kernel with the RT PREEMPT patch, or to install the Xenomai co-kernel next to it. The PR2 (which runs the pr2_mechanism package, the precursor to ros_control) has an RT PREEMPT patched kernel.

Whatever system is used, 'real-time-ness' can be configured with a per-thread granularity. So even if 'the rest' of ROS is not inherently real-time, parts of nodes can be made to be deterministically scheduled and executed. In the case of ros_control, the main loop responsible for executing all the instantiated controllers is an example of such a real-time thread. As such, the controller plugins themselves execute in a real-time context.

The fact that ROS itself (which is an ambiguous thing to say anyway) is not real-time does not really matter.

how does that relate to package realtime_tools ?

One of the main issues when programming on / within real-time (sub)systems is breaking the determinism achieved by the scheduler. To avoid this -- without a priori checked execution times and things like time-slicing and round-robin -- every process under the real-time scheduler basically has to make sure it doesn't hog the cpu for too long (ie: it should yield often enough). Any service (not a ROS service, but a syscall fi) that a process depends on which cannot be interrupted could potentially make this impossible. Memory allocation is one such service: if an allocation request results in a page fault, all bets are off wrt how long it takes the OS and the hardware to handle it. Locking of resources between non- and real-time threads (mutexes, semaphores) is also something that needs to be done with care, as priority inversions might cause undesirable scheduling latencies.

The realtime_tools package provides implementations of the ROS publish and subscribe mechanism that take these limitations into account. Memory allocation in the real-time components is done in the initialisation phase, and all dynamic message handling is done by non-real-time helper threads that would not cause any problems if they did require non-real-time safe services.


Some related questions (which I did not see in the Related questions box:

The doc for ros_control says controller_manager provides a hard RT loop.

knowing that ROS is designed for non-RT OS (plain linux), how is that possible on a non-RT OS?

It isn't. Not without first making Linux capable of some deterministic scheduling and execution.

Two well known ways to add deterministic scheduling to a Linux system are to patch the kernel with the RT PREEMPT patch, or to install the Xenomai co-kernel next to it. The PR2 (which runs the pr2_mechanism package, the precursor to ros_control) has an RT PREEMPT patched kernel.

Whatever system is used, 'real-time-ness' can be configured with a per-thread granularity. So even if 'the rest' of ROS is not inherently real-time, parts of nodes can be made to be deterministically scheduled and executed. In the case of ros_control, the main loop responsible for executing all the instantiated controllers is an example of such a real-time thread. As such, the controller plugins themselves execute in a real-time context.

The fact that ROS itself (which is an ambiguous thing to say anyway) is not real-time does not really matter.

The only thing you need to take care of now is to make sure that you can safely communicate with the real-time parts of your node.

how does that relate to package realtime_tools ?

One of the main issues when programming on / within real-time (sub)systems is breaking the determinism achieved by the scheduler. To avoid this -- without a priori checked execution times and things like time-slicing and round-robin -- every process under the real-time scheduler basically has to make sure it doesn't hog the cpu for too long (ie: it should yield often enough). Any service (not a ROS service, but a syscall fi) that a process depends on which cannot be interrupted could potentially make this impossible. Memory allocation is one such service: if an allocation request results in a page fault, all bets are off wrt how long it takes the OS and the hardware to handle it. Locking of resources between non- and real-time threads (mutexes, semaphores) is also something that needs to be done with care, as priority inversions might cause undesirable scheduling latencies.

The realtime_tools package provides implementations of the ROS publish and subscribe mechanism that take these limitations into account. Memory allocation in the real-time components is done in the initialisation phase, and all dynamic message handling is done by non-real-time helper threads that would not cause any problems if they did require non-real-time safe services.


Some related questions (which I did not see in the Related questions box: