mirror of https://github.com/ArduPilot/ardupilot
Plane: Support a long failsafe that goes straight to auto
This is very useful with an aircraft that is expected to be autonomously operating in auto from takeoff to landing. It is convient to have a GCS connected or RC, but the loss of either isn't considered a reason to terminate the mission.
This commit is contained in:
parent
d69b8c2693
commit
24c5fe54df
|
@ -424,8 +424,8 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
|
||||
// @Param: FS_LONG_ACTN
|
||||
// @DisplayName: Long failsafe action
|
||||
// @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTION is set to 3, the parachute will be deployed (make sure the chute is configured and enabled).
|
||||
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute
|
||||
// @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTN is set to 3, the parachute will be deployed (make sure the chute is configured and enabled). If FS_LONG_ACTN is set to 4 the aircraft will switch to mode AUTO with the current waypoint if it is not already in mode AUTO, unless it is in the middle of a landing sequence.
|
||||
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute,4:Auto
|
||||
// @User: Standard
|
||||
GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE),
|
||||
|
||||
|
|
|
@ -44,6 +44,7 @@ enum failsafe_action_long {
|
|||
FS_ACTION_LONG_RTL = 1,
|
||||
FS_ACTION_LONG_GLIDE = 2,
|
||||
FS_ACTION_LONG_PARACHUTE = 3,
|
||||
FS_ACTION_LONG_AUTO = 4,
|
||||
};
|
||||
|
||||
// type of stick mixing enabled
|
||||
|
|
|
@ -134,6 +134,8 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||
#endif
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(mode_fbwa, reason);
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
|
||||
set_mode(mode_auto, reason);
|
||||
} else {
|
||||
set_mode(mode_rtl, reason);
|
||||
}
|
||||
|
@ -172,12 +174,18 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, ModeReason reason
|
|||
#endif
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(mode_fbwa, reason);
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
|
||||
set_mode(mode_auto, reason);
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_RTL) {
|
||||
set_mode(mode_rtl, reason);
|
||||
}
|
||||
break;
|
||||
|
||||
case Mode::Number::RTL:
|
||||
if (g.fs_action_long == FS_ACTION_LONG_AUTO) {
|
||||
set_mode(mode_auto, reason);
|
||||
}
|
||||
break;
|
||||
#if HAL_QUADPLANE_ENABLED
|
||||
case Mode::Number::QLAND:
|
||||
case Mode::Number::QRTL:
|
||||
|
|
Loading…
Reference in New Issue