From 7374e5d84e027f8059bd07f1dab28a9a1ad55d01 Mon Sep 17 00:00:00 2001 From: James Bielman Date: Wed, 9 Jan 2013 10:18:04 -0800 Subject: [PATCH] ArduCopter: Use 16-bit arithmetic when comparing event tick counters. - On the ARM, once the tick counter wrapped, we stopped running events because the wraparound case wasn't being handled correctly. Make sure the comparison is 16 bits to prevent this. --- ArduCopter/ArduCopter.pde | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 734cc9234c..da251d6515 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1038,7 +1038,13 @@ static uint16_t event_time_available(void) static void run_events(uint16_t time_available_usec) { for (uint8_t i=0; i= pgm_read_word(&timer_events[i].time_interval_10ms)) { + // Make sure to use 16-bit arithmetic here for this comparison + // to handle the rollover case. Due to C integer promotion + // rules, we have to force the type of the difference here to + // "uint16_t" or the compiler will do a 32-bit comparison on a + // 32-bit platform. + uint16_t dt = tick_counter - timer_counters[i]; + if (dt >= pgm_read_word(&timer_events[i].time_interval_10ms)) { // this event is due to run. Do we have enough time to run it? event_time_allowed = pgm_read_word(&timer_events[i].min_time_usec); if (event_time_allowed <= time_available_usec) {