AR_AttitudeControl: fix get_throttle_out_speed use of passed in limits

This commit is contained in:
Randy Mackay 2021-09-09 10:33:46 +09:00
parent 61a7387dd9
commit 570c12215d

View File

@ -594,7 +594,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor
}
// calculate final output
float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (_throttle_limit_low || _throttle_limit_high));
float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (motor_limit_low || motor_limit_high || _throttle_limit_low || _throttle_limit_high));
throttle_out += _throttle_speed_pid.get_ff();
throttle_out += throttle_base;