mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
HAL_ChibiOS: removed restriction on delay in threads
threads other than the main thread should be able to sleep, but not call the delay callback
This commit is contained in:
parent
0e29bcc4ab
commit
a489c93001
@ -176,16 +176,14 @@ bool Scheduler::check_called_boost(void)
|
||||
|
||||
void Scheduler::delay(uint16_t ms)
|
||||
{
|
||||
if (!in_main_thread()) {
|
||||
//chprintf("ERROR: delay() from timer process\n");
|
||||
return;
|
||||
}
|
||||
uint64_t start = AP_HAL::micros64();
|
||||
|
||||
while ((AP_HAL::micros64() - start)/1000 < ms) {
|
||||
delay_microseconds(1000);
|
||||
if (_min_delay_cb_ms <= ms) {
|
||||
call_delay_cb();
|
||||
if (in_main_thread()) {
|
||||
call_delay_cb();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user