mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
Copter: added FS_THR_ENABLED_ALWAYS_LAND (=3) option: don't attempt RTL, just land
This commit is contained in:
parent
b00e5d95c9
commit
917edcab11
@ -283,7 +283,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: FS_THR_ENABLE
|
// @Param: FS_THR_ENABLE
|
||||||
// @DisplayName: Throttle Failsafe Enable
|
// @DisplayName: Throttle Failsafe Enable
|
||||||
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
|
||||||
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode
|
// @Values: 0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode,3:Enabled always LAND
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED),
|
GSCALAR(failsafe_throttle, "FS_THR_ENABLE", FS_THR_DISABLED),
|
||||||
|
|
||||||
|
@ -502,6 +502,7 @@
|
|||||||
#define FS_THR_DISABLED 0
|
#define FS_THR_DISABLED 0
|
||||||
#define FS_THR_ENABLED_ALWAYS_RTL 1
|
#define FS_THR_ENABLED_ALWAYS_RTL 1
|
||||||
#define FS_THR_ENABLED_CONTINUE_MISSION 2
|
#define FS_THR_ENABLED_CONTINUE_MISSION 2
|
||||||
|
#define FS_THR_ENABLED_ALWAYS_LAND 3
|
||||||
|
|
||||||
#ifndef FS_THR_VALUE_DEFAULT
|
#ifndef FS_THR_VALUE_DEFAULT
|
||||||
# define FS_THR_VALUE_DEFAULT 975
|
# define FS_THR_VALUE_DEFAULT 975
|
||||||
|
@ -18,6 +18,9 @@ static void failsafe_radio_on_event()
|
|||||||
// if throttle is zero disarm motors
|
// if throttle is zero disarm motors
|
||||||
if (g.rc_3.control_in == 0) {
|
if (g.rc_3.control_in == 0) {
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
|
}else if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
|
||||||
|
// if failsafe_throttle is 3 (i.e. FS_THR_ENABLED_ALWAYS_LAND) land immediately
|
||||||
|
set_mode(LAND);
|
||||||
}else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
}else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}else{
|
}else{
|
||||||
@ -34,11 +37,17 @@ static void failsafe_radio_on_event()
|
|||||||
// We are very close to home so we will land
|
// We are very close to home so we will land
|
||||||
set_mode(LAND);
|
set_mode(LAND);
|
||||||
}
|
}
|
||||||
|
}else if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
|
||||||
|
// if failsafe_throttle is 3 (i.e. FS_THR_ENABLED_ALWAYS_LAND) land immediately
|
||||||
|
set_mode(LAND);
|
||||||
}
|
}
|
||||||
// if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything
|
// if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
|
||||||
|
// if failsafe_throttle is 3 (i.e. FS_THR_ENABLED_ALWAYS_LAND) land immediately
|
||||||
|
set_mode(LAND);
|
||||||
|
}else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}else{
|
}else{
|
||||||
// We have no GPS or are very close to home so we will land
|
// We have no GPS or are very close to home so we will land
|
||||||
@ -77,7 +86,10 @@ static void low_battery_event(void)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case AUTO:
|
case AUTO:
|
||||||
if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) {
|
||||||
|
// if failsafe_throttle is 3 (i.e. FS_THR_ENABLED_ALWAYS_LAND) land immediately
|
||||||
|
set_mode(LAND);
|
||||||
|
}else if(ap.home_is_set == true && g_gps->status() == GPS::GPS_OK_FIX_3D && home_distance > wp_nav.get_waypoint_radius()) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}else{
|
}else{
|
||||||
// We have no GPS or are very close to home so we will land
|
// We have no GPS or are very close to home so we will land
|
||||||
|
Loading…
Reference in New Issue
Block a user