diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index afad2ab3ff..3e3ce4c4f1 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -995,7 +995,7 @@ void AC_PosControl::update_z_controller() // ensure imax is always large enough to overpower hover throttle if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) { - _pid_accel_z.imax(_motors.get_throttle_hover() * 1000.0f); + _pid_accel_z.set_imax(_motors.get_throttle_hover() * 1000.0f); } float thr_out; if (_vibe_comp_enabled) {