mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: Battery failsafe triggers RTL only if we are more than 15m from home, otherwise it performs a LAND
This commit is contained in:
parent
dad2d2b800
commit
a80f065188
@ -75,8 +75,12 @@ static void low_battery_event(void)
|
||||
}
|
||||
break;
|
||||
case AUTO:
|
||||
// To-Do: check distance to home before initiating RTL?
|
||||
if(ap.home_is_set == true && home_distance >= FS_THR_RTL_MIN_DISTANCE) {
|
||||
set_mode(RTL);
|
||||
}else{
|
||||
// We have no GPS or are very close to home so we will land
|
||||
set_mode(LAND);
|
||||
}
|
||||
break;
|
||||
default:
|
||||
set_mode(LAND);
|
||||
|
Loading…
Reference in New Issue
Block a user