Permalink
Browse files

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.
  • Loading branch information...
1 parent 4ba3a8e commit fc03139ccbaf1ce1cb64b6532dba69a9728d2eb9 @jamesjb jamesjb committed Jan 9, 2013
Showing with 7 additions and 1 deletion.
  1. +7 −1 ArduCopter/ArduCopter.pde
@@ -1029,7 +1029,13 @@ static uint16_t event_time_available(void)
static void run_events(uint16_t time_available_usec)
{
for (uint8_t i=0; i<NUM_TIMER_EVENTS; i++) {
- if (tick_counter - timer_counters[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) {

0 comments on commit fc03139

Please sign in to comment.