0
$\begingroup$

Rosanswers logo

We are designing the software stack for an autonomous racing vehicle. The high speeds require good real-time capabilities of the software stack. Are there some resources on best practices or tutorials on this topic? The ros2 documentation provides some information on this but it doesn't go into detail on e.g. how to configure the operating system or how to design your overall node architecture.

Thanks in advance!


Originally posted by awischnewski on ROS Answers with karma: 13 on 2021-07-20

Post score: 1

$\endgroup$

2 Answers 2

0
$\begingroup$

Rosanswers logo

As part of the ROS Real-time Working Group (RTWG) we have the idea to create several guides to help ROS 2 users to develop real-time applications. Please take a look at the RTWG documentation and our current roadmap. https://ros-realtime.github.io/. As you can see some topics are planned but are still WIP and there is no information available yet. Hopefully, we will be able to complete all these tasks in the next few months.

In the remainder of this answer, we collected some guidelines you could follow to improve your application's real-time performance in the meanwhile.

With respect to the Linux kernel, if your application really needs real-time performance we suggest that you use the full Preempt-RT kernel. We created a guide to explain how to build and configure Raspberry PI 4 with Preempt-RT using a docker-based tool linux-real-time-kernel-builder.. While this is only for the RPI4, the guide should help you to understand the steps to build the kernel and the settings we are using. Additionally, you can take a look at this presentation which gives a good overview of how to configure the kernel:

Depending on the computing device you are using you may have to configure additional settings (i.e: disable hyper-threading, disable NMIs, etc)

Finally, you should use cyclictest (https://wiki.linuxfoundation.org/realtime/documentation/howto/tools/cyclictest/start) to check the real-time performance you are getting with your system and your configuration. This is important because this allows you to catch issues with your configuration and your system and provides a baseline of the performance you could get.

Using CPU isolation or CPU affinity could help to improve the performance of your application. Note with this approach you would reduce the overall CPU available bandwidth of your system because your non-real-time applications won't be scheduled in the isolated CPUs. This approach could make sense if you have a clear separation of real-time and non-real-time applications in your system, and enough CPU for all your applications.

With respect to assigning RT priorities, one thing you could do is to separate node tasks in different callback groups depending on their priority and run them in different threads with different priorities. Here is an example https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor. Additionally, some DDS implementations allow to fine-tune their internal thread priorities and CPU affinities. For example, in the case of CycloneDDS it is possible to set the stack size, scheduling class, and scheduling priority for each thread (https://github.com/eclipse-cyclonedds/cyclonedds/blob/master/docs/manual/config.rst#thread-configuration). Note that if your real-time application depends on network communications you will have to tune the kernel network-related threads accordingly to the priorities you're setting in your application (see https://arxiv.org/pdf/1808.10821.pdf).

Here I'm listing some additional points related to memory management, blocking calls, etc.

  1. Lock the process memory to avoid memory page faults
  1. Allocate the memory before the node transitions into the active state.
  1. Use a real-time capable allocator
  1. Use real-time capable containers https://gitlab.com/ApexAI/apex_containers
  2. Use bounded or fixed-size data types
  • In Apex.OS all message types are upper bounded
  • In ROS 2 you could patch the messages you are using and set an upper bound depending on your application requirements
  1. Avoid logging macro calls in the real-time code path
  • In Apex.OS we have a real-time logger that avoids using any kind of potentially blocking calls such as e.g. cerr, fprintf, ... and instead uses DDS network communication to send the log data to the non-safety critical partition where it gets written to a file.
  • In ROS 2 you replace your logging macros with a real-time logger or remove them from your real-time path and log from a non-real-time thread
  1. In Multi-threaded applications blocking synchronization primitives such as mutexes may suffer from priority inversion
  1. Detection of memory allocation and blocking system calls

I hope this information helps to improve your performance. I would encourage you to attend the RTWG and present your use case there. You will certainly get additional tips and support from other participants there.


Originally posted by carlossvg with karma: 116 on 2021-07-21

This answer was ACCEPTED on the original site

Post score: 9

$\endgroup$
0
$\begingroup$

Rosanswers logo

At the Executor Workshop at ROS World 2021, several talks were given about this topic, how to make ROS 2 applications real-time, efficient and deterministic. Presentation-videos, slides and code examples including a real-time Linux kernel image for RapsPi are available (see real-time working group pages).

ROS 2 Executor Workshop (ROSWorld 2021) https://www.apex.ai/roscon-21

Reference system: https://github.com/ros-realtime/reference-system


Originally posted by JanStaschulat with karma: 81 on 2022-04-01

This answer was NOT ACCEPTED on the original site

Post score: 2

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.