From 693ce27bf6c15226dda1eef6f27f868931b5b3d8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 12 Mar 2014 15:19:45 +0900 Subject: [PATCH] Plane: pass eeprom start to Mission constructor --- ArduPlane/ArduPlane.pde | 4 ++-- ArduPlane/defines.h | 18 ++++-------------- 2 files changed, 6 insertions(+), 16 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index f07e3b5a23..bc51ff2be5 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -580,7 +580,7 @@ static int32_t nav_pitch_cd; static bool start_command(const AP_Mission::Mission_Command& cmd); static bool verify_command(const AP_Mission::Mission_Command& cmd); static void exit_mission(); -AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission); +AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission, MISSION_START_BYTE, MISSION_END_BYTE); //////////////////////////////////////////////////////////////////////////////// // Waypoint distances @@ -749,7 +749,7 @@ static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = { }; // setup the var_info table -AP_Param param_loader(var_info, WP_START_BYTE); +AP_Param param_loader(var_info, MISSION_START_BYTE); void setup() { cliSerial = hal.console; diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 02ee6aefcf..7c45a708fd 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -179,29 +179,19 @@ enum log_messages { // which a groundstart will be // triggered - -// 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 -#define WP_SIZE 15 - // fence points are stored at the end of the EEPROM #define MAX_FENCEPOINTS 20 #define FENCE_WP_SIZE sizeof(Vector2l) -#define FENCE_START_BYTE (EEPROM_MAX_ADDR-(MAX_FENCEPOINTS*FENCE_WP_SIZE)) +#define FENCE_START_BYTE (HAL_STORAGE_SIZE_AVAILABLE-(MAX_FENCEPOINTS*FENCE_WP_SIZE)) // rally points shoehorned between fence points and waypoints #define MAX_RALLYPOINTS 10 #define RALLY_WP_SIZE 15 #define RALLY_START_BYTE (FENCE_START_BYTE-(MAX_RALLYPOINTS*RALLY_WP_SIZE)) -#define MAX_WAYPOINTS ((RALLY_START_BYTE - WP_START_BYTE) / WP_SIZE) - 1 // - - // 1 - // to - // be - // safe +// parameters get the first 1280 bytes of EEPROM, mission commands are stored between these params and the rally points +#define MISSION_START_BYTE 0x500 +#define MISSION_END_BYTE (RALLY_START_BYTE-1) // convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps // to -1)