Browse Source

Plane: tailsitter: dont check if flying its always true in vtol transtion

apm_2208
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
040e08f4b1
  1. 2
      ArduPlane/tailsitter.cpp

2
ArduPlane/tailsitter.cpp

@ -294,7 +294,7 @@ void Tailsitter::output(void) @@ -294,7 +294,7 @@ void Tailsitter::output(void)
// handle forward flight modes and transition to VTOL modes
if (!active() || in_vtol_transition()) {
// get FW controller throttle demand and mask of motors enabled during forward flight
if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait && quadplane.is_flying()) {
if (hal.util->get_soft_armed() && in_vtol_transition() && !quadplane.throttle_wait) {
/*
during transitions to vtol mode set the throttle to hover thrust, center the rudder
*/

Loading…
Cancel
Save