Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Try using SCHED_FIFO on any kernel #1142

Merged
merged 2 commits into from
Dec 20, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 12 additions & 3 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,9 @@ Determinism
-----------

For best performance when controlling hardware you want the controller manager to have as little jitter as possible in the main control loop.
The normal linux kernel is optimized for computational throughput and therefore is not well suited for hardware control.
The two easiest kernel options are the `Real-time Ubuntu 22.04 LTS Beta <https://ubuntu.com/blog/real-time-ubuntu-released>`_ or `linux-image-rt-amd64 <https://packages.debian.org/bullseye/linux-image-rt-amd64>`_ on Debian Bullseye.

If you have a realtime kernel installed, the main thread of Controller Manager attempts to configure ``SCHED_FIFO`` with a priority of ``50``.
Independent of the kernel installed, the main thread of Controller Manager attempts to
configure ``SCHED_FIFO`` with a priority of ``50``.
By default, the user does not have permission to set such a high priority.
To give the user such permissions, add a group named realtime and add the user controlling your robot to this group:

Expand All @@ -36,6 +35,16 @@ Afterwards, add the following limits to the realtime group in ``/etc/security/li

The limits will be applied after you log out and in again.

The normal linux kernel is optimized for computational throughput and therefore is not well suited for hardware control.
Alternatives to the standard kernel include

- `Real-time Ubuntu 22.04 LTS Beta <https://ubuntu.com/blog/real-time-ubuntu-released>`_ on Ubuntu 22.04
- `linux-image-rt-amd64 <https://packages.debian.org/bullseye/linux-image-rt-amd64>`_ on Debian Bullseye
- lowlatency kernel (``sudo apt install linux-lowlatency``) on any ubuntu

Though installing a realtime-kernel will definitely get the best results when it comes to low
jitter, using a lowlatency kernel can improve things a lot with being really easy to install.

Parameters
-----------

Expand Down
16 changes: 7 additions & 9 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,16 +48,14 @@ int main(int argc, char ** argv)
std::thread cm_thread(
[cm]()
{
if (realtime_tools::has_realtime_kernel())
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
{
if (!realtime_tools::configure_sched_fifo(kSchedPriority))
{
RCLCPP_WARN(cm->get_logger(), "Could not enable FIFO RT scheduling policy");
}
}
else
{
RCLCPP_INFO(cm->get_logger(), "RT kernel is recommended for better performance");
RCLCPP_WARN(
cm->get_logger(),
"Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO RT "
"scheduling. See "
"[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
"for details.");
}

// for calculating sleep time
Expand Down
Loading