mirror of https://github.com/ArduPilot/ardupilot
go back to 1024 bytes for variables in EEPROM
This commit is contained in:
parent
f5f6e2d4ec
commit
50f9d12ad5
|
@ -345,8 +345,8 @@ enum gcs_severity {
|
|||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP
|
||||
// parameters get the first 1024 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
|
||||
#define WP_SIZE 15
|
||||
|
||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||
|
|
|
@ -200,8 +200,8 @@ enum gcs_severity {
|
|||
|
||||
// EEPROM addresses
|
||||
#define EEPROM_MAX_ADDR 4096
|
||||
// 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
|
||||
// parameters get the first 1024 bytes of EEPROM, remainder is for waypoints
|
||||
#define WP_START_BYTE 0x400 // 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