From d372907a983f4cfe41782f5f7e6913ef53eddaae Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 22 Aug 2021 00:59:39 +0100 Subject: [PATCH] Plane: Quadplane: add Q_OPTION to only allow arming in Qmodes and auto. --- ArduPlane/AP_Arming.cpp | 6 ++++++ ArduPlane/quadplane.cpp | 2 +- ArduPlane/quadplane.h | 1 + 3 files changed, 8 insertions(+), 1 deletion(-) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 057bec9238..8caccccf2f 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -116,6 +116,12 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) ret = false; } + if (plane.quadplane.enabled() && ((plane.quadplane.options & QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO) != 0) && + !plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto)) { + check_failed(display_failure,"not in Q mode"); + ret = false; + } + return ret; } diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 1faed04684..b98242beaa 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -306,7 +306,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: OPTIONS // @DisplayName: quadplane options // @Description: Level Transition:Keep wings within LEVEL_ROLL_LIMIT and only use forward motor(s) for climb during transition, Allow FW Takeoff: If bit is not set then NAV_TAKEOFF command on quadplanes will instead perform a NAV_VTOL takeoff, Allow FW Land:If bit is not set then NAV_LAND command on quadplanes will instead perform a NAV_VTOL_LAND, Vtol Takeoff Frame: command NAV_VTOL_TAKEOFF altitude is as set by the command's reference frame rather than a delta above current location, Use FW Approach:Use a fixed wing approach for VTOL landings, USE QRTL:instead of QLAND for rc failsafe when in VTOL modes, Use Governor:Use ICE Idle Governor in MANUAL for forward motor, Force Qassist: on always,Mtrs_Only_Qassist: in tailsitters only, uses VTOL motors and not flying surfaces for QASSIST, Airmode_On_Arm:Airmode enabled when arming by aux switch, Disarmed Yaw Tilt:Enable motor tilt for yaw when disarmed, Delay Spoolup:Delay VTOL spoolup for 2 seconds after arming, ThrLandControl: enable throttle stick control of landing rate, DisableApproach: Disable use of approach and airbrake stages in VTOL landing, EnableLandResponsition: enable pilot controlled repositioning in AUTO land. Descent will pause while repositioning. - // @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Use FW Approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,9:Airmode_On_Arm,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandResponsition + // @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Use FW Approach,5:Use QRTL,6:Use Governor,7:Force Qassist,8:Mtrs_Only_Qassist,9:Airmode_On_Arm,10:Disarmed Yaw Tilt,11:Delay Spoolup,12:disable Qassist based on synthetic airspeed,13:Disable Ground Effect Compensation,14:Ignore forward flight angle limits in Qmodes,15:ThrLandControl,16:DisableApproach,17:EnableLandResponsition,18:Only allow arming in Qmodes or auto AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0), AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2), diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 1c1fd28b92..dcc03ef225 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -543,6 +543,7 @@ private: OPTION_THR_LANDING_CONTROL=(1<<15), OPTION_DISABLE_APPROACH=(1<<16), OPTION_REPOSITION_LANDING=(1<<17), + OPTION_ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18), }; AP_Float takeoff_failure_scalar;