mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: failsafe RTL vs LAND decision always based on 2m
Previously this decision was based on the WPNAV_RADIUS parameter which is unexpected (and undocumented) behaviour. Better just to hard-code it to 2m and remove the dependency on this parameter.
This commit is contained in:
parent
d00f9b61b4
commit
58774222c3
@ -238,6 +238,11 @@
|
||||
# define FS_GCS_TIMEOUT_MS 5000 // gcs failsafe triggers after 5 seconds with no GCS heartbeat
|
||||
#endif
|
||||
|
||||
// possible values for FS_GCS parameter
|
||||
#define FS_GCS_DISABLED 0
|
||||
#define FS_GCS_ENABLED_ALWAYS_RTL 1
|
||||
#define FS_GCS_ENABLED_CONTINUE_MISSION 2
|
||||
|
||||
// Radio failsafe while using RC_override
|
||||
#ifndef FS_RADIO_RC_OVERRIDE_TIMEOUT_MS
|
||||
# define FS_RADIO_RC_OVERRIDE_TIMEOUT_MS 1000 // RC Radio failsafe triggers after 1 second while using RC_override from ground station
|
||||
@ -248,10 +253,9 @@
|
||||
#define FS_RADIO_TIMEOUT_MS 500 // RC Radio Failsafe triggers after 500 miliseconds with No RC Input
|
||||
#endif
|
||||
|
||||
// possible values for FS_GCS parameter
|
||||
#define FS_GCS_DISABLED 0
|
||||
#define FS_GCS_ENABLED_ALWAYS_RTL 1
|
||||
#define FS_GCS_ENABLED_CONTINUE_MISSION 2
|
||||
#ifndef FS_CLOSE_TO_HOME_CM
|
||||
# define FS_CLOSE_TO_HOME_CM 200 // if vehicle within 2m of home, vehicle will LAND instead of RTL during some failsafes
|
||||
#endif
|
||||
|
||||
// pre-arm baro vs inertial nav max alt disparity
|
||||
#ifndef PREARM_MAX_ALT_DISPARITY_CM
|
||||
|
@ -26,7 +26,7 @@ void Copter::failsafe_radio_on_event()
|
||||
set_mode_land_with_pause();
|
||||
|
||||
// if far from home then RTL
|
||||
}else if(home_distance > wp_nav.get_wp_radius()) {
|
||||
} else if(home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
|
||||
@ -47,7 +47,7 @@ void Copter::failsafe_radio_on_event()
|
||||
|
||||
// if failsafe_throttle is FS_THR_ENABLED_ALWAYS_RTL do RTL
|
||||
} else if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
|
||||
if(home_distance > wp_nav.get_wp_radius()) {
|
||||
if (home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
@ -75,7 +75,7 @@ void Copter::failsafe_radio_on_event()
|
||||
set_mode_land_with_pause();
|
||||
|
||||
// if far from home then RTL
|
||||
}else if(home_distance > wp_nav.get_wp_radius()) {
|
||||
} else if(home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
@ -117,7 +117,7 @@ void Copter::failsafe_battery_event(void)
|
||||
init_disarm_motors();
|
||||
}else{
|
||||
// set mode to RTL or LAND
|
||||
if (g.failsafe_battery_enabled == FS_BATT_RTL && home_distance > wp_nav.get_wp_radius()) {
|
||||
if (g.failsafe_battery_enabled == FS_BATT_RTL && home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
@ -131,7 +131,7 @@ void Copter::failsafe_battery_event(void)
|
||||
init_disarm_motors();
|
||||
|
||||
// set mode to RTL or LAND
|
||||
} else if (home_distance > wp_nav.get_wp_radius()) {
|
||||
} else if (home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
} else {
|
||||
@ -145,7 +145,7 @@ void Copter::failsafe_battery_event(void)
|
||||
init_disarm_motors();
|
||||
|
||||
// set mode to RTL or LAND
|
||||
} else if (g.failsafe_battery_enabled == FS_BATT_RTL && home_distance > wp_nav.get_wp_radius()) {
|
||||
} else if (g.failsafe_battery_enabled == FS_BATT_RTL && home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
} else {
|
||||
@ -212,7 +212,7 @@ void Copter::failsafe_gcs_check()
|
||||
// if throttle is zero disarm motors
|
||||
if (ap.throttle_zero || ap.land_complete) {
|
||||
init_disarm_motors();
|
||||
}else if(home_distance > wp_nav.get_wp_radius()) {
|
||||
}else if(home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
@ -226,7 +226,7 @@ void Copter::failsafe_gcs_check()
|
||||
init_disarm_motors();
|
||||
// if g.failsafe_gcs is 1 do RTL, 2 means continue with the mission
|
||||
} else if (g.failsafe_gcs == FS_GCS_ENABLED_ALWAYS_RTL) {
|
||||
if (home_distance > wp_nav.get_wp_radius()) {
|
||||
if (home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
@ -241,7 +241,7 @@ void Copter::failsafe_gcs_check()
|
||||
// if landed disarm
|
||||
if (ap.land_complete) {
|
||||
init_disarm_motors();
|
||||
} else if (home_distance > wp_nav.get_wp_radius()) {
|
||||
} else if (home_distance > FS_CLOSE_TO_HOME_CM) {
|
||||
// switch to RTL or if that fails, LAND
|
||||
set_mode_RTL_or_land_with_pause();
|
||||
}else{
|
||||
|
Loading…
Reference in New Issue
Block a user