From f4c1b6a3c607336d208b412abb3e7774e71d6876 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Mar 2012 20:46:49 +1100 Subject: [PATCH] SITL: ensure we don't run the sitl timer twice this caused problems with random() --- libraries/Desktop/support/sitl.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/Desktop/support/sitl.cpp b/libraries/Desktop/support/sitl.cpp index 205522898d..9ee53f4440 100644 --- a/libraries/Desktop/support/sitl.cpp +++ b/libraries/Desktop/support/sitl.cpp @@ -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; }