From a7b1252b51dbd21878e5651960953da92b8531be Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 18 Jul 2012 22:50:22 -0700 Subject: [PATCH] arducopter alt hold state reset --- ArduCopter/system.pde | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 52fc483b2f..4c912cabb8 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -439,11 +439,10 @@ static void set_mode(byte mode) motors.auto_armed(g.rc_3.control_in > 0); // clearing value used in interactive alt hold - manual_boost = 0; + reset_throttle_counter = 0; // clearing value used to force the copter down in landing mode landing_boost = 0; - reset_throttle_flag = false; // do we want to come to a stop or pass a WP? slow_wp = false;