From 6bfcd28adeda4620cfd40c529d791b1faa63b1bb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 13 Jul 2013 19:49:25 +0900 Subject: [PATCH] Copter: thr failsafe will not RTL if in batt failsafe resolves issue #413 --- ArduCopter/events.pde | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde index 6ed0fa93a2..9adb87c8bc 100644 --- a/ArduCopter/events.pde +++ b/ArduCopter/events.pde @@ -43,6 +43,11 @@ static void failsafe_radio_on_event() } // if failsafe_throttle is 2 (i.e. FS_THR_ENABLED_CONTINUE_MISSION) no need to do anything break; + case LAND: + // continue to land if battery failsafe is also active otherwise fall through to default handling + if (g.failsafe_battery_enabled && ap.low_battery) { + break; + } default: if(g.failsafe_throttle == FS_THR_ENABLED_ALWAYS_LAND) { // if failsafe_throttle is 3 (i.e. FS_THR_ENABLED_ALWAYS_LAND) land immediately