From 50f9d12ad59b50fb32113aa25e592d375a0f3a13 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Feb 2012 09:56:17 +1100 Subject: [PATCH] go back to 1024 bytes for variables in EEPROM --- ArduCopter/defines.h | 4 ++-- ArduPlane/defines.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 5a476279be..502e868233 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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 diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 1ed15dd9b7..4b54294e53 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -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