From 8639676eb366d16d657a69e21ceedde5822b0587 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 27 Mar 2014 10:40:00 +1100 Subject: [PATCH] Plane: we need 5 points for a valid geofence the first and last points need to be the same for it to be a closed polygon --- ArduPlane/geofence.pde | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/geofence.pde b/ArduPlane/geofence.pde index 7edd289915..2130dafa08 100644 --- a/ArduPlane/geofence.pde +++ b/ArduPlane/geofence.pde @@ -6,8 +6,9 @@ #if GEOFENCE_ENABLED == ENABLED -#define MIN_GEOFENCE_POINTS 4 //3 to define a minimal polygon (triangle) - //+ 1 for return point. +#define MIN_GEOFENCE_POINTS 5 // 3 to define a minimal polygon (triangle) + // + 1 for return point and +1 for last + // pt (same as first) /* * The state of geo-fencing. This structure is dynamically allocated