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:
parent
b1a3e0a537
commit
d07f8aa42b
@ -874,6 +874,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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user