From fd9b16e787fdac62e42679909e5e1aee9691a104 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 1 Nov 2011 09:27:49 -0700 Subject: [PATCH] resetting alt hold I --- ArduCopter/system.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 2f7d46e5fe..c4b6573378 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -512,6 +512,7 @@ init_throttle_cruise() // are we moving from manual throttle to auto_throttle? if((old_control_mode <= STABILIZE) && (g.rc_3.control_in > MINIMUM_THROTTLE)){ g.pi_throttle.reset_I(); + g.pi_alt_hold.reset_I(); #if FRAME_CONFIG == HELI_FRAME g.throttle_cruise.set_and_save(heli_get_scaled_throttle(g.rc_3.control_in)); #else