Plane: transition pitch limit should not apply to FBWA

pilot should be able to override pitch, very important on motor
failure to control glide
This commit is contained in:
Andrew Tridgell 2023-01-24 17:38:25 +11:00
parent 64d03555af
commit 6623f1156c
1 changed files with 5 additions and 0 deletions

View File

@ -4275,6 +4275,11 @@ void SLT_Transition::set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_
return;
}
if (!plane.control_mode->does_auto_throttle()) {
// don't limit pitch when in manually controlled modes like FBWA, ACRO
return;
}
float max_pitch;
if (transition_state < TRANSITION_TIMER) {
if (plane.ahrs.groundspeed() < 3.0) {