mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scheduler: use task -3 for wait_for_sample()
This commit is contained in:
parent
e801821f0c
commit
4888583e17
@ -232,7 +232,9 @@ float AP_Scheduler::load_average()
|
||||
void AP_Scheduler::loop()
|
||||
{
|
||||
// wait for an INS sample
|
||||
hal.util->persistent_data.scheduler_task = -3;
|
||||
AP::ins().wait_for_sample();
|
||||
hal.util->persistent_data.scheduler_task = -1;
|
||||
|
||||
const uint32_t sample_time_us = AP_HAL::micros();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user