mirror of https://github.com/ArduPilot/ardupilot
Plane: add Q_OPTION for RTL always on RC failsafe for ship landing
This commit is contained in:
parent
e7ceb359a7
commit
71cc0dc02d
|
@ -54,7 +54,9 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, ModeReason reaso
|
|||
case Mode::Number::QAUTOTUNE:
|
||||
#endif
|
||||
case Mode::Number::QACRO:
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_RTL) {
|
||||
set_mode(mode_rtl, reason);
|
||||
} else if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
set_mode(mode_qrtl, reason);
|
||||
} else {
|
||||
set_mode(mode_qland, reason);
|
||||
|
@ -147,7 +149,9 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||
#if QAUTOTUNE_ENABLED
|
||||
case Mode::Number::QAUTOTUNE:
|
||||
#endif
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_RTL) {
|
||||
set_mode(mode_rtl, reason);
|
||||
} else if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
set_mode(mode_qrtl, reason);
|
||||
} else {
|
||||
set_mode(mode_qland, reason);
|
||||
|
|
|
@ -257,7 +257,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, EnableLandResposition: enable pilot controlled repositioning in AUTO land. Descent will pause while repositioning. ARMVTOL: Arm only in VTOL or AUTO modes. CompleteTransition: to fixed wing if Q_TRANS_FAIL timer times out instead of QLAND.
|
||||
// @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:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL
|
||||
// @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:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL, 20: Force RTL mode on VTOL failsafes overriding bit 5(USE QRTL)
|
||||
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
||||
|
||||
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
||||
|
|
|
@ -523,6 +523,7 @@ private:
|
|||
OPTION_REPOSITION_LANDING=(1<<17),
|
||||
OPTION_ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18),
|
||||
OPTION_TRANS_FAIL_TO_FW=(1<<19),
|
||||
OPTION_FS_RTL=(1<<20),
|
||||
};
|
||||
|
||||
AP_Float takeoff_failure_scalar;
|
||||
|
|
Loading…
Reference in New Issue