AP_Scheduler: use task -3 for wait_for_sample()

This commit is contained in:
Andrew Tridgell 2019-05-17 09:00:22 +10:00
parent e801821f0c
commit 4888583e17

View File

@ -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();