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