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
This commit is contained in:
Andrew Tridgell 2014-03-27 10:40:00 +11:00
parent 268b1e85a1
commit 8639676eb3
1 changed files with 3 additions and 2 deletions

View File

@ -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