diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 983e59ccf9568d8bcfab9a3abf5551d349ff47bc..63728fa746e3367bd889f5d4542ed2db05cdec84 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1800,7 +1800,7 @@ bool set_throttle_mode( uint8_t new_throttle_mode ) set_new_altitude(current_loc.alt); // by default hold the current altitude if ( throttle_mode <= THROTTLE_MANUAL_TILT_COMPENSATED ) { // reset the alt hold I terms if previous throttle mode was manual reset_throttle_I(); - set_accel_throttle_I_from_pilot_throttle(); + set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in)); } throttle_initialised = true; break; diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 4aa846e384265ff89d9aaca24807af7ea4f5249e..eb39a3b2800571467141a68289e423045b7df72a 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -1196,10 +1196,10 @@ static void reset_throttle_I(void) g.pid_throttle_accel.reset_I(); } -static void set_accel_throttle_I_from_pilot_throttle(void) +static void set_accel_throttle_I_from_pilot_throttle(int16_t pilot_throttle) { // shift difference between pilot's throttle and hover throttle into accelerometer I - g.pid_throttle_accel.set_integrator(g.rc_3.control_in-g.throttle_cruise); + g.pid_throttle_accel.set_integrator(pilot_throttle-g.throttle_cruise); } static void reset_stability_I(void)