AC_PosControl: Change motors.get_throttle_out

to get_throttle to follow function renaming in AP_Motors
This commit is contained in:
Robert Lefebvre 2015-05-14 21:02:40 -04:00 committed by Randy Mackay
parent b8181b6b90
commit e87ca6de6f
1 changed files with 1 additions and 1 deletions

View File

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