-
Notifications
You must be signed in to change notification settings - Fork 90
Description
Currently, realtime_helpers.cpp offers configure_sched_fifo to set thread priority. however, the function sets the policy to SCHED_FIFO. In a PREEMPT_RT kernel, where multiple threads could have RT priority, SCHED_FIFO threads may not rotate. A SCHED_RR policy may be better.
realtime_tools/realtime_tools/src/realtime_helpers.cpp
Lines 74 to 99 in e668fb5
| bool configure_sched_fifo(int priority) | |
| { | |
| #ifdef _WIN32 | |
| HANDLE thread = GetCurrentThread(); | |
| return SetThreadPriority(thread, priority); | |
| #elif defined(__APPLE__) | |
| // macOS implementation using pthread_setschedparam with SCHED_FIFO | |
| pthread_t thread = pthread_self(); | |
| struct sched_param schedp; | |
| memset(&schedp, 0, sizeof(schedp)); | |
| schedp.sched_priority = priority; | |
| int policy = SCHED_FIFO; | |
| if (pthread_setschedparam(thread, policy, &schedp) == 0) { | |
| return true; | |
| } else { | |
| // Optionally log strerror(errno) for debugging | |
| return false; | |
| } | |
| #else | |
| struct sched_param schedp; | |
| memset(&schedp, 0, sizeof(schedp)); | |
| schedp.sched_priority = priority; | |
| return !sched_setscheduler(0, SCHED_FIFO, &schedp); | |
| #endif | |
| } |
I've started to use realtime_helpers.cpp in ros2control hardware interfaces and think it would be better if there was an option to opt for another policy i.e SCHED_RR.
I propose adding a new configure_sched_rr function that uses the SCHED_RR policy.
https://stackoverflow.com/questions/9392415/linux-sched-other-sched-fifo-and-sched-rr-differences
https://man7.org/linux/man-pages/man7/sched.7.html