ArduCopter: replace FS_THR_RTL_MIN_DISTANCE with wp_radius

This effectively means that an RTL kicked off by a failsafe will
immediately switch to LAND mode only if within 2 meters.  Previously the
radius was much wider (15m).
This commit is contained in:
Randy Mackay 2013-01-12 11:40:03 +09:00
parent 37b66700b4
commit cad9533398
2 changed files with 4 additions and 8 deletions

View File

@ -441,10 +441,6 @@
# define FS_THR_VALUE_DEFAULT 975
#endif
#ifndef FS_THR_RTL_MIN_DISTANCE
# define FS_THR_RTL_MIN_DISTANCE 1500 // the minimum distance from home in which
#endif
#ifndef MINIMUM_THROTTLE
# define MINIMUM_THROTTLE 130

View File

@ -21,7 +21,7 @@ static void failsafe_on_event()
// if throttle is zero disarm motors
if (g.rc_3.control_in == 0) {
init_disarm_motors();
}else if(ap.home_is_set == true && home_distance >= FS_THR_RTL_MIN_DISTANCE) {
}else if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
set_mode(RTL);
}else{
// We have no GPS or are very close to home so we will land
@ -31,7 +31,7 @@ static void failsafe_on_event()
case AUTO:
// failsafe_throttle is 1 do RTL, 2 means continue with the mission
if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
if(home_distance >= FS_THR_RTL_MIN_DISTANCE) {
if(home_distance > g.waypoint_radius) {
set_mode(RTL);
}else{
// We are very close to home so we will land
@ -41,7 +41,7 @@ static void failsafe_on_event()
// if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything
break;
default:
if(ap.home_is_set == true && home_distance >= FS_THR_RTL_MIN_DISTANCE) {
if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
set_mode(RTL);
}else{
// We have no GPS or are very close to home so we will land
@ -77,7 +77,7 @@ static void low_battery_event(void)
}
break;
case AUTO:
if(ap.home_is_set == true && home_distance >= FS_THR_RTL_MIN_DISTANCE) {
if(ap.home_is_set == true && home_distance > g.waypoint_radius) {
set_mode(RTL);
}else{
// We have no GPS or are very close to home so we will land