Plane: fixed a bug in transition to QSTABILIZE for tailsitters

this bug was found bug Marco on his tailsitter. It resulted in zero
throttle for 2s in transition from FBWA to QSTABILIZE
This commit is contained in:
Andrew Tridgell 2018-04-25 17:21:11 +10:00
parent e6942c53fd
commit 1686ae41d2

View File

@ -915,6 +915,9 @@ bool QuadPlane::is_flying(void)
if (motors->get_throttle() > 0.01f && !motors->limit.throttle_lower) {
return true;
}
if (in_tailsitter_vtol_transition()) {
return true;
}
return false;
}