mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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:
parent
19abdc3cd3
commit
9ad6f711f8
@ -501,10 +501,6 @@
|
|||||||
# define FS_THR_VALUE_DEFAULT 975
|
# define FS_THR_VALUE_DEFAULT 975
|
||||||
#endif
|
#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
|
#ifndef MINIMUM_THROTTLE
|
||||||
# define MINIMUM_THROTTLE 130
|
# define MINIMUM_THROTTLE 130
|
||||||
|
@ -18,7 +18,7 @@ static void failsafe_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(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);
|
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
|
||||||
@ -28,7 +28,7 @@ static void failsafe_on_event()
|
|||||||
case AUTO:
|
case AUTO:
|
||||||
// failsafe_throttle is 1 do RTL, 2 means continue with the mission
|
// failsafe_throttle is 1 do RTL, 2 means continue with the mission
|
||||||
if (g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_RTL) {
|
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);
|
set_mode(RTL);
|
||||||
}else{
|
}else{
|
||||||
// We are very close to home so we will land
|
// We are very close to home so we will land
|
||||||
@ -38,7 +38,7 @@ static void failsafe_on_event()
|
|||||||
// 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 && home_distance >= FS_THR_RTL_MIN_DISTANCE) {
|
if(ap.home_is_set == true && home_distance > g.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 +77,7 @@ static void low_battery_event(void)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case AUTO:
|
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);
|
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