Browse Source

Plane: fixed tailsitter ANGLE_WAIT transition

we need vtol control during transition from hover to fwd flight
master
Andrew Tridgell 7 years ago
parent
commit
214434a2d7
  1. 12
      ArduPlane/tailsitter.cpp

12
ArduPlane/tailsitter.cpp

@ -31,7 +31,17 @@ bool QuadPlane::is_tailsitter(void) @@ -31,7 +31,17 @@ bool QuadPlane::is_tailsitter(void)
*/
bool QuadPlane::tailsitter_active(void)
{
return is_tailsitter() && in_vtol_mode();
if (!is_tailsitter()) {
return false;
}
if (in_vtol_mode()) {
return true;
}
// check if we are in ANGLE_WAIT transition
if (transition_state == TRANSITION_ANGLE_WAIT) {
return true;
}
return false;
}
/*

Loading…
Cancel
Save