From 3ce005a4363828076f3f68513af93fc2a5125703 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Wed, 26 Jun 2013 11:56:58 +0900
Subject: [PATCH] Copter: GPS Failsafe switch to LAND if circular fence enabled

---
 ArduCopter/events.pde | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/ArduCopter/events.pde b/ArduCopter/events.pde
index 7a4aa6085..9714a0017 100644
--- a/ArduCopter/events.pde
+++ b/ArduCopter/events.pde
@@ -140,6 +140,11 @@ static void failsafe_gps_check()
     // take action based on flight mode
     if(mode_requires_GPS(control_mode))
         set_mode(LAND);
+
+    // land if circular fence is enabled
+    if((fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) != 0) {
+        set_mode(LAND);
+    }
 }
 
 // failsafe_gps_off_event - actions to take when GPS contact is restored
-- 
GitLab