Browse Source

AP_Scheduler: use task -3 for wait_for_sample()

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
4888583e17
  1. 2
      libraries/AP_Scheduler/AP_Scheduler.cpp

2
libraries/AP_Scheduler/AP_Scheduler.cpp

@ -232,7 +232,9 @@ float AP_Scheduler::load_average()
void AP_Scheduler::loop() void AP_Scheduler::loop()
{ {
// wait for an INS sample // wait for an INS sample
hal.util->persistent_data.scheduler_task = -3;
AP::ins().wait_for_sample(); AP::ins().wait_for_sample();
hal.util->persistent_data.scheduler_task = -1;
const uint32_t sample_time_us = AP_HAL::micros(); const uint32_t sample_time_us = AP_HAL::micros();

Loading…
Cancel
Save