diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index eddc98b90b..fe41e665a0 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -848,7 +848,8 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) check_attitude_relax(); // normal control modes for VTOL and FW flight - if (in_vtol_mode()) { + // tailsitter in transition to VTOL flight is not really in a VTOL mode yet + if (in_vtol_mode() && !in_tailsitter_vtol_transition()) { // tailsitter-only body-frame roll control options // Angle mode attitude control for pitch and body-frame roll, rate control for euler yaw.