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.
This commit is contained in:
James Bielman 2013-01-09 10:18:04 -08:00 committed by Pat Hickey
parent 0160a10ba7
commit 7374e5d84e
1 changed files with 7 additions and 1 deletions

View File

@ -1038,7 +1038,13 @@ static uint16_t event_time_available(void)
static void run_events(uint16_t time_available_usec) static void run_events(uint16_t time_available_usec)
{ {
for (uint8_t i=0; i<NUM_TIMER_EVENTS; i++) { 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? // 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); event_time_allowed = pgm_read_word(&timer_events[i].min_time_usec);
if (event_time_allowed <= time_available_usec) { if (event_time_allowed <= time_available_usec) {