mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_HAL_ChibiOS: set scheduler task to -4 when running callback tasks
This commit is contained in:
parent
402c8a5e4d
commit
3a38aeda59
@ -224,7 +224,10 @@ void Scheduler::delay(uint16_t ms)
|
||||
delay_microseconds(1000);
|
||||
if (_min_delay_cb_ms <= ms) {
|
||||
if (in_main_thread()) {
|
||||
const auto old_task = hal.util->persistent_data.scheduler_task;
|
||||
hal.util->persistent_data.scheduler_task = -4;
|
||||
call_delay_cb();
|
||||
hal.util->persistent_data.scheduler_task = old_task;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user