mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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
e6942c53fd
commit
1686ae41d2
@ -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;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user