mirror of https://github.com/ArduPilot/ardupilot
Plane: added a value for RTL_AUTOLAND to disable arming check
set RTL_AUTOLAND=3 to get go-around but not RTL DO_LAND_START usage
This commit is contained in:
parent
97e13afd1e
commit
3aa52bb5ee
|
@ -368,7 +368,7 @@ bool AP_Arming_Plane::mission_checks(bool report)
|
|||
{
|
||||
// base checks
|
||||
bool ret = AP_Arming::mission_checks(report);
|
||||
if (plane.mission.get_landing_sequence_start() > 0 && plane.g.rtl_autoland.get() == 0) {
|
||||
if (plane.mission.get_landing_sequence_start() > 0 && plane.g.rtl_autoland == RtlAutoland::RTL_DISABLE) {
|
||||
ret = false;
|
||||
check_failed(ARMING_CHECK_MISSION, report, "DO_LAND_START set and RTL_AUTOLAND disabled");
|
||||
}
|
||||
|
|
|
@ -716,10 +716,10 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
|
||||
// @Param: RTL_AUTOLAND
|
||||
// @DisplayName: RTL auto land
|
||||
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location.
|
||||
// @Values: 0:Disable,1:Enable - go HOME then land,2:Enable - go directly to landing sequence
|
||||
// @Description: Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. If this is set to 0 and there is a DO_LAND_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around without it changing RTL behaviour. For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).
|
||||
// @Values: 0:Disable,1:Fly HOME then land,2:Go directly to landing sequence, 3:OnlyForGoAround
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_autoland, "RTL_AUTOLAND", 0),
|
||||
GSCALAR(rtl_autoland, "RTL_AUTOLAND", float(RtlAutoland::RTL_DISABLE)),
|
||||
|
||||
// @Param: CRASH_ACC_THRESH
|
||||
// @DisplayName: Crash Deceleration Threshold
|
||||
|
|
|
@ -362,7 +362,7 @@ public:
|
|||
AP_Int16 sysid_my_gcs;
|
||||
AP_Int8 telem_delay;
|
||||
|
||||
AP_Int8 rtl_autoland;
|
||||
AP_Enum<RtlAutoland> rtl_autoland;
|
||||
|
||||
AP_Int8 crash_accel_threshold;
|
||||
|
||||
|
|
|
@ -50,6 +50,15 @@ enum class StickMixing {
|
|||
VTOL_YAW = 3,
|
||||
};
|
||||
|
||||
// values for RTL_AUTOLAND
|
||||
enum class RtlAutoland {
|
||||
RTL_DISABLE = 0,
|
||||
RTL_THEN_DO_LAND_START = 1,
|
||||
RTL_IMMEDIATE_DO_LAND_START = 2,
|
||||
NO_RTL_GO_AROUND = 3,
|
||||
};
|
||||
|
||||
|
||||
enum ChannelMixing {
|
||||
MIXING_DISABLED = 0,
|
||||
MIXING_UPUP = 1,
|
||||
|
|
|
@ -261,7 +261,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
|
|||
#endif
|
||||
if (!already_landing) {
|
||||
// never stop a landing if we were already committed
|
||||
if (g.rtl_autoland == 2 && plane.mission.is_best_land_sequence()) {
|
||||
if (g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START && plane.mission.is_best_land_sequence()) {
|
||||
// continue mission as it will reach a landing in less distance
|
||||
plane.mission.set_in_landing_sequence_flag(true);
|
||||
break;
|
||||
|
|
|
@ -75,7 +75,7 @@ void ModeRTL::navigate()
|
|||
}
|
||||
#endif
|
||||
|
||||
if (plane.g.rtl_autoland == 1 &&
|
||||
if (plane.g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START &&
|
||||
!plane.auto_state.checked_for_autoland &&
|
||||
plane.reached_loiter_target() &&
|
||||
labs(plane.altitude_error_cm) < 1000) {
|
||||
|
@ -90,7 +90,7 @@ void ModeRTL::navigate()
|
|||
// on every loop
|
||||
plane.auto_state.checked_for_autoland = true;
|
||||
}
|
||||
else if (plane.g.rtl_autoland == 2 &&
|
||||
else if (plane.g.rtl_autoland == RtlAutoland::RTL_IMMEDIATE_DO_LAND_START &&
|
||||
!plane.auto_state.checked_for_autoland) {
|
||||
// Go directly to the landing sequence
|
||||
if (plane.mission.jump_to_landing_sequence()) {
|
||||
|
|
Loading…
Reference in New Issue