Plane: Quadplane: tiltrotor: add Q_OPTION to keep motors tilted up when disarmed in FW modes
This commit is contained in:
parent
07f915ecf0
commit
6bad9ac4d7
@ -258,7 +258,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||||||
// @Param: OPTIONS
|
// @Param: OPTIONS
|
||||||
// @DisplayName: quadplane 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, Always use FW spiral approach:Always use Use a fixed wing spiral 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. Force RTL mode: forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL).
|
// @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, Always use FW spiral approach:Always use Use a fixed wing spiral 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. Force RTL mode: forces RTL mode on rc failsafe in VTOL modes overriding bit 5(USE_QRTL).
|
||||||
// @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Always use FW spiral 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:EnableLandReposition,18:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL, 20: Force RTL mode on VTOL failsafes overriding bit 5(USE QRTL)
|
// @Bitmask: 0:Level Transition,1:Allow FW Takeoff,2:Allow FW Land,3:Vtol Takeoff Frame,4:Always use FW spiral 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:EnableLandReposition,18:ARMVtol, 19: CompleteTransition if Q_TRANS_FAIL, 20: Force RTL mode on VTOL failsafes overriding bit 5(USE QRTL), 21:Tilt rotor tilt motors up when disarmed in FW modes (except manual) to prevent ground strikes
|
||||||
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
||||||
|
|
||||||
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
||||||
|
@ -557,6 +557,7 @@ private:
|
|||||||
ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18),
|
ONLY_ARM_IN_QMODE_OR_AUTO=(1<<18),
|
||||||
TRANS_FAIL_TO_FW=(1<<19),
|
TRANS_FAIL_TO_FW=(1<<19),
|
||||||
FS_RTL=(1<<20),
|
FS_RTL=(1<<20),
|
||||||
|
DISARMED_TILT_UP=(1<<21),
|
||||||
};
|
};
|
||||||
bool option_is_set(OPTION option) const {
|
bool option_is_set(OPTION option) const {
|
||||||
return (options.get() & int32_t(option)) != 0;
|
return (options.get() & int32_t(option)) != 0;
|
||||||
|
@ -219,7 +219,10 @@ void Tiltrotor::continuous_update(void)
|
|||||||
if (!quadplane.in_vtol_mode() && (!hal.util->get_soft_armed() || !quadplane.assisted_flight)) {
|
if (!quadplane.in_vtol_mode() && (!hal.util->get_soft_armed() || !quadplane.assisted_flight)) {
|
||||||
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
|
// we are in pure fixed wing mode. Move the tiltable motors all the way forward and run them as
|
||||||
// a forward motor
|
// a forward motor
|
||||||
slew(get_forward_flight_tilt());
|
|
||||||
|
// option set then if disarmed move to VTOL position to prevent ground strikes, allow tilt forward in manual mode for testing
|
||||||
|
const bool disarmed_tilt_up = !hal.util->get_soft_armed() && (plane.control_mode != &plane.mode_manual) && quadplane.option_is_set(QuadPlane::OPTION::DISARMED_TILT_UP);
|
||||||
|
slew(disarmed_tilt_up ? 0.0 : get_forward_flight_tilt());
|
||||||
|
|
||||||
max_change = tilt_max_change(false);
|
max_change = tilt_max_change(false);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user