From 5b6f7f0012a85e47f049193c64505ee21e7ed53f Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sat, 18 Aug 2012 21:45:49 +0900 Subject: [PATCH] ArduCopter: modified altitude hold so that 1 second slow down period is executed after pilot moves throttle back into deadzone --- ArduCopter/ArduCopter.pde | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index b39e276ec5..82bb95f4a5 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1824,12 +1824,16 @@ void update_throttle_mode(void) break; } + // allow 1 second of slow down after pilot moves throttle back into deadzone if(reset_throttle_counter > 0){ reset_throttle_counter--; + // if 1 second has passed set the target altitude to the current altitude if(reset_throttle_counter == 0){ force_new_altitude(max(current_loc.alt, 100)); }else{ nav_throttle = get_throttle_rate(0); + g.rc_3.servo_out = g.throttle_cruise + nav_throttle + angle_boost; + break; } }