From 75459b09be0ec92c022da9a17ed789ad962b727c Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 19 Aug 2012 11:49:28 +0900 Subject: [PATCH] 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. --- ArduCopter/ArduCopter.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 579817c619..996f13bbc2 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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;