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

This commit is contained in:
Iampete1 2022-02-12 20:23:48 +00:00 committed by Andrew Tridgell
parent 0793814f5a
commit 040e08f4b1
1 changed files with 1 additions and 1 deletions

View File

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