mirror of https://github.com/ArduPilot/ardupilot
Plane: continue limiting pitch during last phase of transition
this prevents a very high pitch demand causing the plane to slow down to below assist speed
This commit is contained in:
parent
926c37a876
commit
115d089904
|
@ -755,6 +755,8 @@ void QuadPlane::update_transition(void)
|
||||||
if (transition_state < TRANSITION_TIMER) {
|
if (transition_state < TRANSITION_TIMER) {
|
||||||
// set a single loop pitch limit in TECS
|
// set a single loop pitch limit in TECS
|
||||||
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
|
plane.TECS_controller.set_pitch_max_limit(transition_pitch_max);
|
||||||
|
} else if (transition_state < TRANSITION_DONE) {
|
||||||
|
plane.TECS_controller.set_pitch_max_limit((transition_pitch_max+1)*2);
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (transition_state) {
|
switch (transition_state) {
|
||||||
|
|
Loading…
Reference in New Issue