mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: Disarm On Land
After a landing has occur using a LAND waypoint, automatically disarm after this many seconds have passed. Use 0 to not disarm.
This commit is contained in:
parent
90bb97a144
commit
1b0ed277b3
@ -134,6 +134,7 @@ public:
|
|||||||
k_param_cli_enabled,
|
k_param_cli_enabled,
|
||||||
k_param_trim_rc_at_start,
|
k_param_trim_rc_at_start,
|
||||||
k_param_hil_mode,
|
k_param_hil_mode,
|
||||||
|
k_param_land_disarm_delay,
|
||||||
|
|
||||||
// 100: Arming parameters
|
// 100: Arming parameters
|
||||||
k_param_arming = 100,
|
k_param_arming = 100,
|
||||||
@ -437,6 +438,7 @@ public:
|
|||||||
AP_Int32 airspeed_cruise_cm;
|
AP_Int32 airspeed_cruise_cm;
|
||||||
AP_Int32 RTL_altitude_cm;
|
AP_Int32 RTL_altitude_cm;
|
||||||
AP_Float land_flare_alt;
|
AP_Float land_flare_alt;
|
||||||
|
AP_Int8 land_disarm_delay;
|
||||||
AP_Int32 min_gndspeed_cm;
|
AP_Int32 min_gndspeed_cm;
|
||||||
AP_Int16 pitch_trim_cd;
|
AP_Int16 pitch_trim_cd;
|
||||||
AP_Int16 FBWB_min_altitude_cm;
|
AP_Int16 FBWB_min_altitude_cm;
|
||||||
|
@ -232,6 +232,15 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
ASCALAR(land_flare_sec, "LAND_FLARE_SEC", 2.0),
|
ASCALAR(land_flare_sec, "LAND_FLARE_SEC", 2.0),
|
||||||
|
|
||||||
|
// @Param: LAND_DISARMDELAY
|
||||||
|
// @DisplayName: Landing disarm delay
|
||||||
|
// @Description: After a landing has completed using a LAND waypoint, automatically disarm after this many seconds have passed. Use 0 to not disarm.
|
||||||
|
// @Units: seconds
|
||||||
|
// @Increment: 1
|
||||||
|
// @Range: 0 127
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(land_disarm_delay, "LAND_DISARMDELAY", 0),
|
||||||
|
|
||||||
// @Param: NAV_CONTROLLER
|
// @Param: NAV_CONTROLLER
|
||||||
// @DisplayName: Navigation controller selection
|
// @DisplayName: Navigation controller selection
|
||||||
// @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental conrtrollers will be added which are selected using this parameter.
|
// @Description: Which navigation controller to enable. Currently the only navigation controller available is L1. From time to time other experimental conrtrollers will be added which are selected using this parameter.
|
||||||
|
@ -87,6 +87,9 @@ static bool verify_land()
|
|||||||
get_distance(prev_WP_loc, current_loc) + 200);
|
get_distance(prev_WP_loc, current_loc) + 200);
|
||||||
nav_controller->update_waypoint(prev_WP_loc, land_WP_loc);
|
nav_controller->update_waypoint(prev_WP_loc, land_WP_loc);
|
||||||
|
|
||||||
|
// check if we should auto-disarm after a confirmed landing
|
||||||
|
disarm_if_autoland_complete();
|
||||||
|
|
||||||
/*
|
/*
|
||||||
we return false as a landing mission item never completes
|
we return false as a landing mission item never completes
|
||||||
|
|
||||||
@ -96,6 +99,26 @@ static bool verify_land()
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
If land_DisarmDelay is enabled (non-zero), check for a landing then auto-disarm after time expires
|
||||||
|
*/
|
||||||
|
static void disarm_if_autoland_complete()
|
||||||
|
{
|
||||||
|
if (g.land_disarm_delay > 0 &&
|
||||||
|
auto_state.land_complete &&
|
||||||
|
!is_flying() &&
|
||||||
|
arming.arming_required() != AP_Arming::NO &&
|
||||||
|
arming.is_armed()) {
|
||||||
|
/* we have auto disarm enabled. See if enough time has passed */
|
||||||
|
if (hal.scheduler->millis() - auto_state.last_flying_ms >= g.land_disarm_delay*1000UL) {
|
||||||
|
if (disarm_motors()) {
|
||||||
|
gcs_send_text_P(SEVERITY_LOW,PSTR("Auto-Disarmed"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
a special glide slope calculation for the landing approach
|
a special glide slope calculation for the landing approach
|
||||||
|
Loading…
Reference in New Issue
Block a user