AC_AttitudeControl: fixed factor of 1000 error in init_takeoff

This commit is contained in:
Andrew Tridgell 2016-06-21 23:23:31 +10:00
parent 752c1834e1
commit d1b28aaed9

View File

@ -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