mirror of https://github.com/ArduPilot/ardupilot
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:
parent
7cc9ec4d61
commit
75459b09be
|
@ -677,7 +677,7 @@ static int32_t baro_alt;
|
||||||
// The climb_rate as reported by Baro in cm/s
|
// The climb_rate as reported by Baro in cm/s
|
||||||
static int16_t baro_rate;
|
static int16_t baro_rate;
|
||||||
// used to switch out of Manual Boost
|
// 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
|
// used to track when to read sensors vs estimate alt
|
||||||
static boolean alt_sensor_flag;
|
static boolean alt_sensor_flag;
|
||||||
static int16_t saved_toy_throttle;
|
static int16_t saved_toy_throttle;
|
||||||
|
|
Loading…
Reference in New Issue