expand parameter area for ArduPlane

this ensures all parameters can be saved without overflow
This commit is contained in:
Andrew Tridgell 2012-02-12 22:50:23 +11:00
parent d4305e0ae2
commit e85da68fe6

View File

@ -200,8 +200,8 @@ enum gcs_severity {
// EEPROM addresses // EEPROM addresses
#define EEPROM_MAX_ADDR 4096 #define EEPROM_MAX_ADDR 4096
// parameters get the first 1KiB of EEPROM, remainder is for waypoints // parameters get the first 1280 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
// fence points are stored at the end of the EEPROM // fence points are stored at the end of the EEPROM