mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Limit_Geofence: reduce maximum number of fence points to 6 from 20 to save memory
This commit is contained in:
parent
e0393e541c
commit
bff3417d29
@ -20,8 +20,7 @@
|
|||||||
#include <GPS.h>
|
#include <GPS.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define MAX_FENCEPOINTS 6 // Fence points reduced from 20 to 6 to save memory
|
||||||
#define MAX_FENCEPOINTS 20
|
|
||||||
|
|
||||||
class AP_Limit_Geofence : public AP_Limit_Module {
|
class AP_Limit_Geofence : public AP_Limit_Module {
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user