mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_AttitudeControl: fixed factor of 1000 error in init_takeoff
This commit is contained in:
parent
752c1834e1
commit
d1b28aaed9
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user