mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ACM: expanded EEPROM parameter area by 256 bytes
This commit is contained in:
parent
cb2af1ef86
commit
db4fef174b
@ -346,8 +346,8 @@ enum gcs_severity {
|
|||||||
|
|
||||||
// EEPROM addresses
|
// EEPROM addresses
|
||||||
#define EEPROM_MAX_ADDR 4096
|
#define EEPROM_MAX_ADDR 4096
|
||||||
// parameters get the first 1024 bytes of EEPROM, remainder is for waypoints
|
// parameters get the first 1280 bytes of EEPROM, remainder is for waypoints
|
||||||
#define WP_START_BYTE 0x400 // where in memory home WP is stored + all other WP
|
#define WP_START_BYTE 0x500 // where in memory home WP is stored + all other WP
|
||||||
#define WP_SIZE 15
|
#define WP_SIZE 15
|
||||||
|
|
||||||
#define ONBOARD_PARAM_NAME_LENGTH 15
|
#define ONBOARD_PARAM_NAME_LENGTH 15
|
||||||
|
Loading…
Reference in New Issue
Block a user