Plane: Fix tilt rotor surging during high speed QLOITER flight

This commit is contained in:
Paul Riseborough 2023-09-28 14:19:50 +10:00 committed by Andrew Tridgell
parent dcfffefa07
commit d14a88b378
1 changed files with 18 additions and 15 deletions

View File

@ -3007,7 +3007,9 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
q_fwd_throttle = MIN(q_fwd_thr_gain * tanf(fwd_tilt_rad), 1.0f);
// Relax forward tilt limit if the position controller is saturating in the forward direction because
// the forward thrust motor could be failed
// the forward thrust motor could be failed. Do not do this with tilt rotors because they do not rely on
// forward throttle during VTOL flight
if (!tiltrotor.enabled()) {
const float fwd_tilt_range_cd = (float)aparm.angle_max - 100.0f * q_fwd_pitch_lim;
if (is_positive(fwd_tilt_range_cd)) {
// rate limit the forward tilt change to slew between the motor good and motor failed
@ -3023,6 +3025,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) {
// take the lesser of the two limits
q_fwd_pitch_lim_cd = (float)aparm.angle_max;
}
}
float fwd_thr_scaler;
if (!in_vtol_land_approach()) {