From c64a505906178efc522932937647b70507d93344 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 6 Jan 2016 13:29:19 +0900 Subject: [PATCH] AC_PosControl: relax_alt_hold_controllers accepts throttle in 0 to 1 range --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 211f08b40f..9b2714362d 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -241,7 +241,7 @@ void AC_PosControl::relax_alt_hold_controllers(float throttle_setting) _accel_last_z_cms = 0.0f; _accel_target.z = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f; _flags.reset_accel_to_throttle = true; - _pid_accel_z.set_integrator(throttle_setting); + _pid_accel_z.set_integrator(throttle_setting*1000.0f); } // get_alt_error - returns altitude error in cm