Browse Source

SITL: run the timer_scheduler() when there are no SITL packets

otherwise we can block in the ADC code
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
0dc8dd5394
  1. 2
      libraries/Desktop/support/sitl.cpp

2
libraries/Desktop/support/sitl.cpp

@ -269,12 +269,14 @@ static void timer_handler(int signum)
if (update_count == 0) { if (update_count == 0) {
sitl_update_gps(0, 0, 0, 0, 0, false); sitl_update_gps(0, 0, 0, 0, 0, false);
timer_scheduler.run();
SREG = oldSREG; SREG = oldSREG;
in_timer = false; in_timer = false;
return; return;
} }
if (update_count == last_update_count) { if (update_count == last_update_count) {
timer_scheduler.run();
SREG = oldSREG; SREG = oldSREG;
in_timer = false; in_timer = false;
return; return;

Loading…
Cancel
Save