diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index cbe09e2bf2..a5ef8a8ac2 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -252,7 +252,7 @@ void AC_PosControl::init_takeoff() freeze_ff_z(); // shift difference between last motor out and hover throttle into accelerometer I - _pid_accel_z.set_integrator(_motors.get_throttle_out()-_throttle_hover); + _pid_accel_z.set_integrator(_motors.get_throttle()-_throttle_hover); } // is_active_z - returns true if the z-axis position controller has been run very recently