mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
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:
parent
268b1e85a1
commit
8639676eb3
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user