mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed a bug in Q_ASSIST_ modes for tiltrotors
when a tilt-rotor drops below Q_ASSIST_SPEED we need to keep it in the airspeed wait state until it has regained airspeed, otherwise we will end up with too low throttle
This commit is contained in:
parent
6213852fa6
commit
58a363c643
|
@ -1247,8 +1247,10 @@ void QuadPlane::update_transition(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// if rotors are fully forward then we are not transitioning
|
// if rotors are fully forward then we are not transitioning,
|
||||||
if (tiltrotor_fully_fwd()) {
|
// unless we are waiting for airspeed to increase (in which case
|
||||||
|
// the tilt till decrease rapidly)
|
||||||
|
if (tiltrotor_fully_fwd() && transition_state != TRANSITION_AIRSPEED_WAIT) {
|
||||||
transition_state = TRANSITION_DONE;
|
transition_state = TRANSITION_DONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue