Browse Source

the ACM parameters have a max size of 1114 bytes

to ensure that all parameters can be saved, expand parameter area by
256 bytes
master
Andrew Tridgell 13 years ago
parent
commit
16417b651e
  1. 4
      ArduCopter/defines.h

4
ArduCopter/defines.h

@ -345,8 +345,8 @@ enum gcs_severity { @@ -345,8 +345,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 bytes 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
#define ONBOARD_PARAM_NAME_LENGTH 15

Loading…
Cancel
Save