Fix delay(1) rarely returning immediately.
On my RPi4, this once per 5-20k calls that worked.
Reduce the last call to microsleep according to the
remaining time needed in the last loop iteration.
musl implements `sched_*` following the posix standard,
where `sched_setschedule` is used for process scheduling.
Linux implementation defines `sched_*` functions based in
the thread scheduler and not with the process.
Using `pthread_*` should be used to follow such standard.
Ref: https://pubs.opengroup.org/onlinepubs/9699919799/
From: https://www.openwall.com/lists/musl/2016/03/01/5
> ... Linux does not provide a way
> to set scheduling parameters for a _process_, only for threads. The
> sched_setscheduler syscall is documented as taking a pid but actually
> takes a thread id and only operates on that thread. glibc just ignores
> this and provides sched_* functions that do the wrong thing.
This can be fixed by using `pthread_setschedparam` and requesting the current
thread id via `pthread_self`.
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
../../libraries/AP_HAL_Linux/Scheduler.cpp: In member function ‘void Linux::Scheduler::_debug_stack()’:
../../libraries/AP_HAL_Linux/Scheduler.cpp:127:47: warning: format ‘%zu’ expects a matching ‘size_t’ argument [-Wformat=]
_uart_thread.get_stack_usage());
^
The open coded version has the same problem fixed by Thread abstraction:
the order of the calls matters and it's easy to call in the wrong order.
Here pthread_attr_setschedparam() and pthread_attr_setschedpolicy()
should be swapped, like in 62c2f737d5 (AP_HAL_Linux: fix setting RT priorities.)
It's not being sold, there are just a few (different) engineering
samples built and there are no plans for this to go forward for people
that were pushing it.
If a thread other than the main one calls Scheduler::delay() we could
end up triggering the call of delay callbacks. Those should only ever
happen on the main thread.
RPI-based boards that use RCInput_RPI need more stack space otherwise we
end up with stack corruption. This leads to crash particularly when also
using GPIO_RPI since it may change what that driver is poking on memory.
This increases stack size to 1M which is overkill for most of other
boards with a more controllable stack usage. However this exposes that
on multiple different HWs a single point for stack size decision may not
be the best. This can be improved in future.
Several return values in the constructor of the scheduler were ignored
before, while they should be respected.
I found that bug while strac'ing ardupilot as it failed at some later
point.
Signed-off-by: Ralf Ramsauer <ralf.ramsauer@othr.de>