Browse Source

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
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
d07f8aa42b
  1. 3
      ArduPlane/quadplane.cpp

3
ArduPlane/quadplane.cpp

@ -874,6 +874,9 @@ bool QuadPlane::is_flying(void) @@ -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…
Cancel
Save