mirror of https://github.com/ArduPilot/ardupilot
Plane: Added Quadplane option for QRTL failsafe action
This commit is contained in:
parent
9d95933845
commit
44f6f7335e
|
@ -32,7 +32,11 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, mode_reason_t re
|
|||
case Mode::Number::QACRO:
|
||||
failsafe.saved_mode_number = control_mode->mode_number();
|
||||
failsafe.saved_mode_set = true;
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
set_mode(mode_qrtl, reason);
|
||||
} else {
|
||||
set_mode(mode_qland, reason);
|
||||
}
|
||||
break;
|
||||
|
||||
case Mode::Number::AUTO:
|
||||
|
@ -94,7 +98,11 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, mode_reason_t rea
|
|||
case Mode::Number::QLOITER:
|
||||
case Mode::Number::QACRO:
|
||||
case Mode::Number::QAUTOTUNE:
|
||||
if (quadplane.options & QuadPlane::OPTION_FS_QRTL) {
|
||||
set_mode(mode_qrtl, reason);
|
||||
} else {
|
||||
set_mode(mode_qland, reason);
|
||||
}
|
||||
break;
|
||||
|
||||
case Mode::Number::AUTO:
|
||||
|
|
|
@ -328,8 +328,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
|||
|
||||
// @Param: OPTIONS
|
||||
// @DisplayName: quadplane options
|
||||
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the corrent position.
|
||||
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings
|
||||
// @Description: This provides a set of additional control options for quadplanes. LevelTransition means that the wings should be held level to within LEVEL_ROLL_LIMIT degrees during transition to fixed wing flight, and the vehicle will not use the vertical lift motors to climb during the transition. If AllowFWTakeoff bit is not set then fixed wing takeoff on quadplanes will instead perform a VTOL takeoff. If AllowFWLand bit is not set then fixed wing land on quadplanes will instead perform a VTOL land. If respect takeoff frame is not set the vehicle will interpret all takeoff waypoints as an altitude above the corrent position. When Use QRTL is set it will replace QLAND with QRTL for failsafe actions when in VTOL modes.
|
||||
// @Bitmask: 0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand,3:Respect takeoff frame types,4:Use a fixed wing approach for VTOL landings,5:Use QRTL instead of QLAND for failsafe when in VTOL modes.
|
||||
AP_GROUPINFO("OPTIONS", 58, QuadPlane, options, 0),
|
||||
|
||||
AP_SUBGROUPEXTENSION("",59, QuadPlane, var_info2),
|
||||
|
|
|
@ -508,6 +508,7 @@ private:
|
|||
OPTION_ALLOW_FW_LAND=(1<<2),
|
||||
OPTION_RESPECT_TAKEOFF_FRAME=(1<<3),
|
||||
OPTION_MISSION_LAND_FW_APPROACH=(1<<4),
|
||||
OPTION_FS_QRTL=(1<<5),
|
||||
};
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue