From d1b28aaed9f79ce5ce87a46eeed195e739b9e355 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 21 Jun 2016 23:23:31 +1000 Subject: [PATCH] AC_AttitudeControl: fixed factor of 1000 error in init_takeoff --- 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 274ffad387..0010d7f247 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -306,7 +306,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()-_motors.get_throttle_hover()); + _pid_accel_z.set_integrator((_motors.get_throttle()-_motors.get_throttle_hover())*1000.0f); } // is_active_z - returns true if the z-axis position controller has been run very recently