diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index b5c96a1619..f6407420a3 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -430,7 +430,10 @@ void Plane::update_control_mode(void) // ensure we are fly-forward when we are flying as a pure fixed // wing aircraft. This helps the EKF produce better state // estimates as it can make stronger assumptions - if (quadplane.in_vtol_mode() || + if (quadplane.available() && + quadplane.tailsitter.is_in_fw_flight()) { + ahrs.set_fly_forward(true); + } else if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) { ahrs.set_fly_forward(false); } else if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {