Browse Source

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

master
rmackay9 12 years ago committed by Andrew Tridgell
parent
commit
02bf3ea027
  1. 8
      ArduCopter/events.pde

8
ArduCopter/events.pde

@ -75,8 +75,12 @@ static void low_battery_event(void) @@ -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);

Loading…
Cancel
Save