mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: limit pitch to zero during airspeed wait VTOL mode
This commit is contained in:
parent
4f9927beda
commit
4adda34439
@ -726,6 +726,11 @@ void QuadPlane::update_transition(void)
|
|||||||
} else {
|
} else {
|
||||||
assisted_flight = false;
|
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) {
|
switch (transition_state) {
|
||||||
case TRANSITION_AIRSPEED_WAIT: {
|
case TRANSITION_AIRSPEED_WAIT: {
|
||||||
|
Loading…
Reference in New Issue
Block a user