Skip to content

Commit dcad80f

Browse files
authored
Merge pull request #2 from ros-realtime/add-minimal-scheduling
Add minimal_scheduling package
2 parents 1a5c575 + bd210a8 commit dcad80f

13 files changed

+984
-9
lines changed

README.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,9 +5,10 @@ create real-time applications.
55

66
* [minimal_memory_lock](minimal_memory_lock/README.md): shows how to lock the
77
process memory to avoid memory page faults
8-
8+
* [minimal_scheduling](minimal_scheduling/README.md): shows how to configure the thread(s)
9+
scheduling policy and priority
10+
911
TODO: Add other packages after review (currently in rolling-experimental branch):
10-
* minimal_scheduling: shows how to configure the thread(s) scheduling policy and priority (TODO: add SCHED_DEADLINE example)
1112
* minimal_cpu_affinity: shows how to set the process and threads CPU affinity
1213
* minimal_realtime_loop: shows different approaches to created typical real-time time based loops
1314
* minimal_deadline_qos: shows how to use the DDS deadline QoS policy

minimal_scheduling/CMakeLists.txt

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(minimal_scheduling)
3+
4+
# Default to C++14
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 14)
7+
endif()
8+
9+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10+
add_compile_options(-Wall -Wextra -Wpedantic)
11+
endif()
12+
13+
find_package(ament_cmake REQUIRED)
14+
find_package(rclcpp REQUIRED)
15+
find_package(std_msgs REQUIRED)
16+
17+
add_executable(minimal_scheduling_main_thread minimal_scheduling_main_thread.cpp)
18+
ament_target_dependencies(minimal_scheduling_main_thread rclcpp std_msgs)
19+
20+
add_executable(minimal_scheduling_middleware_threads minimal_scheduling_middleware_threads.cpp)
21+
ament_target_dependencies(minimal_scheduling_middleware_threads rclcpp std_msgs)
22+
23+
add_executable(minimal_scheduling_spin_thread minimal_scheduling_spin_thread.cpp)
24+
ament_target_dependencies(minimal_scheduling_spin_thread rclcpp std_msgs)
25+
26+
add_executable(minimal_scheduling_callback_group minimal_scheduling_callback_group.cpp)
27+
ament_target_dependencies(minimal_scheduling_callback_group rclcpp std_msgs)
28+
29+
install(TARGETS
30+
minimal_scheduling_main_thread
31+
minimal_scheduling_middleware_threads
32+
minimal_scheduling_spin_thread
33+
minimal_scheduling_callback_group
34+
DESTINATION lib/${PROJECT_NAME}
35+
)
36+
37+
if(BUILD_TESTING)
38+
find_package(ament_lint_auto REQUIRED)
39+
ament_lint_auto_find_test_dependencies()
40+
endif()
41+
42+
ament_package()

minimal_scheduling/README.md

Lines changed: 212 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,212 @@
1+
# minimal_scheduling
2+
3+
These examples show how to configure the thread scheduling policy and priority using
4+
[pthread APIs](https://linux.die.net/man/7/pthreads).
5+
6+
In order to show the effects of using a real-time scheduling policy, the examples show
7+
the number of involuntary context switches in each callback execution. An involuntary context
8+
switches happens when the kernel scheduler preempts a task to schedule a higher priority thread
9+
or by a I/O request.
10+
11+
Using a real-time scheduling policy and using a real-time priority removes or reduces the
12+
number of involuntary context switches.
13+
14+
**Note: The code shown in the examples is not necessarily real-time safe. The aim of these
15+
examples is to show a minimal usage example for a particular concept.**
16+
17+
## Requirements
18+
19+
Adjust permissions for the scheduler. Add to `/etc/security/limits.conf` (as sudo):
20+
21+
```bash
22+
<your username> - rtprio 98
23+
```
24+
25+
## How to run
26+
27+
### minimal_scheduling_main_thread
28+
29+
For this example, we will be configuring the main thread scheduling policy of the main thread,
30+
where the node is spinning. In this case, the middleware threads will not inherit these settings
31+
because they are created after the scheduling configuration.
32+
33+
## Using SCHED_OTHER scheduling policy
34+
35+
We start with the default settings, which means we don't configure the main thread scheduling
36+
policy and priority. In Linux, by default, the `SCHED_OTHER` scheduling policy is used. Since,
37+
this is not a real-time scheduling policy the main thread might be preempted frequently. For this
38+
reason, we expect to see a high number of involuntary context switches.
39+
40+
```bash
41+
$ ros2 run minimal_scheduling minimal_scheduling_main_thread
42+
```
43+
44+
<script id="asciicast-gxZvQuyvNZQR1Y75nFUCq7GQ8" src="https://asciinema.org/a/gxZvQuyvNZQR1Y75nFUCq7GQ8.js" async></script>
45+
46+
## Using SCHED_FIFO scheduling policy
47+
48+
Now we run the same example but using the `SCHED_FIFO` scheduling policy and setting a priority
49+
of 80.
50+
51+
There are just a few kernel threads running with a higher priority, so we expect to see a few
52+
number of involuntary context switches or none.
53+
54+
```bash
55+
$ ros2 run minimal_scheduling minimal_scheduling_main_thread --sched SCHED_FIFO --priority 80
56+
```
57+
58+
Using `htop` or `ps` we can observe the priorities and the scheduling policies of the threads.
59+
60+
```bash
61+
$ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr
62+
TID COMMAND RTPRIO CLS PSR
63+
6775 minimal_sched_f 80 FF 7
64+
6776 minimal_sched_f - TS 1
65+
6777 gc - TS 1
66+
6778 dq.builtins - TS 0
67+
6779 dq.user - TS 6
68+
6780 tev - TS 2
69+
6781 recv - TS 4
70+
6782 recvMC - TS 0
71+
6783 recvUC - TS 1
72+
6784 minimal_sched_f - TS 0
73+
```
74+
75+
Note we are not configuring the threads created by the RMW middleware. These threads will run
76+
with normal priority. This option might be preferred when middleware communications shall not
77+
participate in the real-time execution. Also, some DDS implementations allow to configure
78+
each thread scheduling individually, allowing to set a priority different creator thread.
79+
80+
<script id="asciicast-XzlFpNwZKw0hea9vhfKFCMgj4" src="https://asciinema.org/a/XzlFpNwZKw0hea9vhfKFCMgj4.js" async></script>
81+
82+
## Using SCHED_RR scheduling policy
83+
84+
Now we run the same example but using the `SCHED_RR` scheduling policy and setting a priority
85+
of 80. We expect to see the same results as in the previous case.
86+
87+
```bash
88+
$ ros2 run minimal_scheduling minimal_scheduling_main_thread --sched SCHED_RR --priority 80
89+
```
90+
91+
Using `htop` or `ps` we can observe the priorities and the scheduling policies of the threads.
92+
93+
```bash
94+
$ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr
95+
TID COMMAND RTPRIO CLS PSR
96+
16359 minimal_schedul 80 RR 3
97+
16360 minimal_schedul - TS 6
98+
16361 gc - TS 1
99+
16362 dq.builtins - TS 6
100+
16363 dq.user - TS 1
101+
16364 tev - TS 5
102+
16365 recv - TS 7
103+
16366 recvMC - TS 0
104+
16367 recvUC - TS 7
105+
16368 minimal_schedul - TS 0
106+
```
107+
108+
<script id="asciicast-OOGN7OVgLkOE4b3ifTPdx6DWr" src="https://asciinema.org/a/OOGN7OVgLkOE4b3ifTPdx6DWr.js" async></script>
109+
110+
### minimal_scheduling_middleware_threads
111+
112+
For this example, we will be configuring the main thread scheduling policy before the node
113+
creation. The middleware threads will inherit these settings because they are created after
114+
the scheduling configuration.
115+
116+
```bash
117+
$ ros2 run minimal_scheduling minimal_scheduling_middleware_threads --sched SCHED_FIFO --priority 80
118+
```
119+
120+
Using `htop` or `ps` we can observe the priorities and the scheduling policies of the threads.
121+
122+
```bash
123+
$ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr
124+
TID COMMAND RTPRIO CLS PSR
125+
6794 minimal_sched_f 80 FF 2
126+
6795 minimal_sched_f 80 FF 6
127+
6796 gc 80 FF 6
128+
6797 dq.builtins 80 FF 3
129+
6798 dq.user 80 FF 6
130+
6799 tev 80 FF 6
131+
6800 recv 80 FF 7
132+
6801 recvMC 80 FF 7
133+
6802 recvUC 80 FF 6
134+
6803 minimal_sched_f 80 FF 7
135+
```
136+
137+
<script id="asciicast-WtoeazuOds4CCpBDA0Mfkg8Ly" src="https://asciinema.org/a/WtoeazuOds4CCpBDA0Mfkg8Ly.js" async></script>
138+
139+
### minimal_scheduling_spin_thread
140+
141+
For this example, we will be configuring the scheduling policy of a thread used to spin the
142+
executor. In this case, the middleware threads will not inherit these settings because
143+
the settings apply only to the executor thread.
144+
145+
```bash
146+
$ ros2 run minimal_scheduling minimal_scheduling_spin_thread --sched SCHED_FIFO --priority 80
147+
```
148+
149+
Using `htop` or `ps` we can observe the priorities and the scheduling policies of the threads.
150+
151+
```bash
152+
$ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr
153+
TID COMMAND RTPRIO CLS PSR
154+
6822 minimal_sched_f - TS 1
155+
6823 minimal_sched_f - TS 7
156+
6824 gc - TS 5
157+
6825 dq.builtins - TS 7
158+
6826 dq.user - TS 2
159+
6827 tev - TS 0
160+
6828 recv - TS 2
161+
6829 recvMC - TS 0
162+
6830 recvUC - TS 7
163+
6831 minimal_sched_f - TS 0
164+
6832 minimal_sched_f 80 FF 7
165+
```
166+
167+
<script id="asciicast-nLpeLDCmtwT5JqH9QYvVPGVXT" src="https://asciinema.org/a/nLpeLDCmtwT5JqH9QYvVPGVXT.js" async></script>
168+
169+
### minimal_scheduling_callback_group
170+
171+
For this example, we will be using multiple callback groups to separate callbacks, so it is
172+
possible to execute them by threads with different scheduling priorities.
173+
174+
We run the example using `SCHED_FIFO` and priority 80 for the thread running the real-time
175+
callbacks. The other callbacks run with normal priority. We expect to see a high number of
176+
involuntary context switches logged only from the non-real-time subscription callbacks.
177+
178+
```bash
179+
$ ros2 run minimal_scheduling minimal_scheduling_callback_group --sched SCHED_FIFO --priority 80
180+
```
181+
182+
Using `htop` or `ps` we can observe the priorities and the scheduling policies of the threads.
183+
184+
```bash
185+
$ ps -C minimal_schedul -L -o tid,comm,rtprio,cls,psr
186+
TID COMMAND RTPRIO CLS PSR
187+
6847 minimal_sched_f - TS 1
188+
6848 minimal_sched_f - TS 0
189+
6849 gc - TS 1
190+
6850 dq.builtins - TS 1
191+
6851 dq.user - TS 7
192+
6852 tev - TS 1
193+
6853 recv - TS 3
194+
6854 recvMC - TS 0
195+
6855 recvUC - TS 7
196+
6856 minimal_sched_f - TS 0
197+
6857 minimal_sched_f 80 FF 0
198+
```
199+
200+
<script id="asciicast-FncZQ5gSgp6sNIxHj4weDra3n" src="https://asciinema.org/a/FncZQ5gSgp6sNIxHj4weDra3n.js" async></script>
201+
202+
## Resources
203+
204+
- [https://www.man7.org/linux/man-pages/man7/sched.7.html](https://www.man7.org/linux/man-pages/man7/sched.7.html)
205+
- [https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start](https://wiki.linuxfoundation.org/realtime/documentation/technical_basics/sched_policy_prio/start)
206+
- [https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base](https://wiki.linuxfoundation.org/realtime/documentation/howto/applications/application_base)
207+
- [https://linux.die.net/man/3/pthread_setschedparam](https://linux.die.net/man/3/pthread_setschedparam)
208+
- [https://linux.die.net/man/3/pthread_create](https://linux.die.net/man/3/pthread_create)
209+
- [https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler](https://access.redhat.com/documentation/en-us/red_hat_enterprise_linux/6/html/performance_tuning_guide/s-cpu-scheduler)
210+
- Callback groups executor - Ralph Lange [video](https://www.youtube.com/watch?v=5Sd5bvvZeb0), [slides](https://www.apex.ai/_files/ugd/984e93_f3791ae0711042a883bfc40f827d6268.pdf)
211+
- [https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor](https://github.com/ros2/examples/tree/master/rclcpp/executors/cbg_executor)
212+
- [Basic investigation of priority of DDS-generated threads.](https://discourse.ros.org/uploads/short-url/p2fAAbrKHkrSqZ9oJkZNwOOf2Hi.pdf)
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
// Copyright (c) 2020 Robert Bosch GmbH
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef MINIMAL_SCHEDULING__BURN_CPU_CYCLES_HPP_
16+
#define MINIMAL_SCHEDULING__BURN_CPU_CYCLES_HPP_
17+
18+
#include <pthread.h>
19+
20+
#include <chrono>
21+
#include <thread>
22+
23+
// Original code taken from:
24+
// https://github.com/ros2/examples/blob/master/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/utilities.hpp
25+
// https://github.com/ros2/examples/blob/14c743af8bbca6a40e83da7a470c5332dce66d9d/rclcpp/executors/cbg_executor/src/examples_rclcpp_cbg_executor/pong_node.cpp#L75-L88
26+
27+
/// Returns the time of the given native thread handle as std::chrono
28+
/// timestamp. This allows measuring the execution time of this thread.
29+
template<typename T>
30+
std::chrono::nanoseconds get_native_thread_time(T native_handle)
31+
{
32+
clockid_t id;
33+
pthread_getcpuclockid(native_handle, &id);
34+
timespec spec;
35+
clock_gettime(id, &spec);
36+
return std::chrono::seconds{spec.tv_sec} + std::chrono::nanoseconds{spec.tv_nsec};
37+
}
38+
39+
/// Returns the time of the current thread as std::chrono timestamp.
40+
/// This allows measuring the execution time of this thread.
41+
inline std::chrono::nanoseconds get_current_thread_time()
42+
{
43+
return get_native_thread_time(pthread_self());
44+
}
45+
46+
void burn_cpu_cycles(std::chrono::nanoseconds duration)
47+
{
48+
if (duration > std::chrono::nanoseconds::zero()) {
49+
auto end_time = get_current_thread_time() + duration;
50+
int x = 0;
51+
bool do_again = true;
52+
while (do_again) {
53+
while (x != std::rand() && x % 1000 != 0) {
54+
x++;
55+
}
56+
do_again = (get_current_thread_time() < end_time);
57+
}
58+
}
59+
}
60+
61+
#endif // MINIMAL_SCHEDULING__BURN_CPU_CYCLES_HPP_

0 commit comments

Comments
 (0)