mirror of https://github.com/ArduPilot/ardupilot
HAL_Linux: don't use usleep() in suspend_timer_procs()
usleep can cause a large delay with PREEMPT kernel
This commit is contained in:
parent
94e14f5dcb
commit
8f280d212b
|
@ -190,7 +190,7 @@ void LinuxScheduler::suspend_timer_procs()
|
|||
{
|
||||
_timer_suspended = true;
|
||||
while (_in_timer_proc) {
|
||||
usleep(1);
|
||||
delay_microseconds(20);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue