From 43762c9fa4d2459fe42a1aa9041eed6ec7de1229 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Mon, 15 Dec 2014 10:45:50 +0900
Subject: [PATCH] Copter: increase GPS_HDOP_GOOD default to 2.3

---
 ArduCopter/config.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index 5c2496ab3..1f2440de4 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -302,7 +302,7 @@
  # define FAILSAFE_GPS_TIMEOUT_MS       5000    // gps failsafe triggers after 5 seconds with no GPS
 #endif
 #ifndef GPS_HDOP_GOOD_DEFAULT
- # define GPS_HDOP_GOOD_DEFAULT         200     // minimum hdop that represents a good position.  used during pre-arm checks if fence is enabled
+ # define GPS_HDOP_GOOD_DEFAULT         230     // minimum hdop that represents a good position.  used during pre-arm checks if fence is enabled
 #endif
 
 // GCS failsafe
-- 
GitLab