From cc89a8cc48c2a30c7203d055081a95cabaa09a9d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 14 Sep 2021 01:11:12 +0100 Subject: [PATCH] Plane: remove airmode Q_OPTION --- ArduPlane/AP_Arming.cpp | 9 --------- ArduPlane/quadplane.cpp | 2 +- ArduPlane/quadplane.h | 2 +- 3 files changed, 2 insertions(+), 11 deletions(-) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 93d6d2bb69..3897d9ddd3 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -220,15 +220,6 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c return false; } -#if HAL_QUADPLANE_ENABLED - if ((method == Method::AUXSWITCH) && (plane.quadplane.options & QuadPlane::OPTION_AIRMODE)) { - // if no airmode switch assigned, honour the QuadPlane option bit: - if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) { - plane.quadplane.air_mode = AirMode::ON; - } - } -#endif - change_arm_state(); // rising edge of delay_arming oneshot diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index d5f6d81dcc..89697294f1 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -268,7 +268,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,18:Only allow arming in Qmodes or auto + // @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,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 66a2f41d0a..806f1b202d 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -509,7 +509,7 @@ private: OPTION_IDLE_GOV_MANUAL=(1<<6), OPTION_Q_ASSIST_FORCE_ENABLE=(1<<7), OPTION_TAILSIT_Q_ASSIST_MOTORS_ONLY=(1<<8), - OPTION_AIRMODE=(1<<9), + OPTION_AIRMODE_UNUSED=(1<<9), OPTION_DISARMED_TILT=(1<<10), OPTION_DELAY_ARMING=(1<<11), OPTION_DISABLE_SYNTHETIC_AIRSPEED_ASSIST=(1<<12),