mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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:
parent
64d03555af
commit
6623f1156c
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user