From 9c59fdfdd68ca4e3a316cb530a40440c1196897e Mon Sep 17 00:00:00 2001 From: unknown Date: Sun, 6 Nov 2011 19:06:13 +0800 Subject: [PATCH] AltHold - another correction to the manual boost. Hopefully properly transferring building up I terms to g.throttle_cruise --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index f2ad56f397..c3c7225769 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1284,14 +1284,14 @@ adjust_altitude() // we remove 0 to 100 PWM from hover manual_boost = g.rc_3.control_in - 180; manual_boost = max(-120, manual_boost); - g.throttle_cruise += g.pi_throttle.get_integrator(); + g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + g.pi_throttle.get_integrator()); g.pi_alt_hold.reset_I(); g.pi_throttle.reset_I(); }else if (g.rc_3.control_in >= 650){ // we add 0 to 100 PWM to hover manual_boost = g.rc_3.control_in - 650; - g.throttle_cruise += g.pi_throttle.get_integrator(); + g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + g.pi_throttle.get_integrator()); g.pi_alt_hold.reset_I(); g.pi_throttle.reset_I();