SITL: ensure we don't run the sitl timer twice

this caused problems with random()
This commit is contained in:
Andrew Tridgell 2012-03-28 20:46:49 +11:00
parent b2d6db9479
commit f4c1b6a3c6

View File

@ -223,7 +223,12 @@ static void sitl_simulator_output(void)
static void timer_handler(int signum)
{
static uint32_t last_update_count;
static bool running;
if (running) {
return;
}
running = true;
cli();
#ifndef __CYGWIN__
@ -261,11 +266,13 @@ static void timer_handler(int signum)
if (update_count == 0) {
sitl_update_gps(0, 0, 0, 0, 0, false);
sei();
running = false;
return;
}
if (update_count == last_update_count) {
sei();
running = false;
return;
}
last_update_count = update_count;
@ -280,6 +287,7 @@ static void timer_handler(int signum)
sitl_update_barometer(sim_state.altitude);
sitl_update_compass(sim_state.rollDeg, sim_state.pitchDeg, sim_state.heading);
sei();
running = false;
}