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:
Andrew Tridgell 2018-07-07 11:51:18 +10:00
parent 0e29bcc4ab
commit a489c93001

View File

@ -176,19 +176,17 @@ 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) {
if (in_main_thread()) {
call_delay_cb();
}
}
}
}
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
{