mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: limit pitch to zero during airspeed wait VTOL mode
This commit is contained in:
parent
4f9927beda
commit
4adda34439
@ -727,6 +727,11 @@ void QuadPlane::update_transition(void)
|
||||
assisted_flight = false;
|
||||
}
|
||||
|
||||
if (transition_state < TRANSITION_TIMER) {
|
||||
// set a single loop pitch limit in TECS
|
||||
plane.TECS_controller.set_pitch_max_limit(0);
|
||||
}
|
||||
|
||||
switch (transition_state) {
|
||||
case TRANSITION_AIRSPEED_WAIT: {
|
||||
// we hold in hover until the required airspeed is reached
|
||||
|
Loading…
Reference in New Issue
Block a user