expand parameter area for ArduPlane
this ensures all parameters can be saved without overflow
This commit is contained in:
parent
d4305e0ae2
commit
e85da68fe6
@ -200,8 +200,8 @@ enum gcs_severity {
|
||||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1KiB of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
|
||||
// parameters get the first 1280 of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP
|
||||
#define WP_SIZE 15
|
||||
|
||||
// fence points are stored at the end of the EEPROM
|
||||
|
Loading…
Reference in New Issue
Block a user