mirror of https://github.com/ArduPilot/ardupilot
SITL: run the timer_scheduler() when there are no SITL packets
otherwise we can block in the ADC code
This commit is contained in:
parent
a71c7b336d
commit
0dc8dd5394
|
@ -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…
Reference in New Issue