diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index bbb74c9b91..1b53b4e9ae 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -4275,4 +4275,28 @@ void QuadPlane::disable_yaw_rate_time_constant() attitude_control->set_yaw_rate_tc(0.0); } +// Check if servo auto trim is allowed, only if countrol surfaces are fully in use +bool QuadPlane::allow_servo_auto_trim() +{ + if (!available()) { + // Quadplane disabled, auto trim always allowed + return true; + } + if (in_vtol_mode()) { + // VTOL motors active in VTOL modes + return false; + } + if (!in_assisted_flight()) { + // In forward flight and VTOL motors not active + return true; + } + if (tailsitter.enabled() && ((options & QuadPlane::OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY) != 0)) { + // Tailsitter in forward flight, motors providing active stabalisation with motors only option + // Control surfaces are running as normal with I term active, motor I term is zeroed + return true; + } + // In forward flight with active VTOL motors + return false; +} + #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 81896f266c..ec1591a158 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -168,6 +168,9 @@ public: // called when we change mode (for any mode, not just Q modes) void mode_enter(void); + // Check if servo auto trim is allowed + bool allow_servo_auto_trim(); + private: AP_AHRS &ahrs; AP_Vehicle::MultiCopter aparm; diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index fb49f2facf..dbaa207fc8 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -1037,7 +1037,7 @@ void Plane::servos_auto_trim(void) return; } #if HAL_QUADPLANE_ENABLED - if (quadplane.in_assisted_flight() || quadplane.in_vtol_mode()) { + if (!quadplane.allow_servo_auto_trim()) { // can't auto-trim with quadplane motors running return; }