ArduCopter: Battery failsafe triggers RTL only if we are more than 15m from home, otherwise it performs a LAND

This commit is contained in:
rmackay9 2012-12-22 18:16:50 +09:00
parent dad2d2b800
commit a80f065188

View File

@ -75,8 +75,12 @@ static void low_battery_event(void)
}
break;
case AUTO:
// To-Do: check distance to home before initiating RTL?
set_mode(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);