ArduCopter: changed reset_throttle_counter to uint8_t to get rid of overflow bug that was preventing target altitude from being locked in after pilot input down throttle.

This commit is contained in:
rmackay9 2012-08-19 11:49:28 +09:00
parent 7cc9ec4d61
commit 75459b09be
1 changed files with 1 additions and 1 deletions

View File

@ -677,7 +677,7 @@ static int32_t baro_alt;
// The climb_rate as reported by Baro in cm/s
static int16_t baro_rate;
// used to switch out of Manual Boost
static int8_t reset_throttle_counter;
static uint8_t reset_throttle_counter;
// used to track when to read sensors vs estimate alt
static boolean alt_sensor_flag;
static int16_t saved_toy_throttle;