Plane: Quadplane: limit manual throttle tilt angle to Q_TILT_MAX

This commit is contained in:
Iampete1 2023-01-16 15:39:24 +00:00 committed by Andrew Tridgell
parent 21a54b5533
commit 20934491e5
1 changed files with 2 additions and 2 deletions

View File

@ -292,9 +292,9 @@ void Tiltrotor::continuous_update(void)
// no manual throttle control, set angle to zero
slew(0);
} else {
// manual control of forward throttle
// manual control of forward throttle up to max VTOL angle
float settilt = .01f * quadplane.forward_throttle_pct();
slew(settilt);
slew(MIN(settilt * max_angle_deg * (1/90.0), get_forward_flight_tilt()));
}
return;
}