diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index 591c1d514a..eb9a20e928 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -126,7 +126,7 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; // must be the first AP_Param variable declared to ensure its // constructor runs before the constructors of the other AP_Param // variables -AP_Param param_loader(var_info, WP_START_BYTE); +AP_Param param_loader(var_info, MISSION_START_BYTE); //////////////////////////////////////////////////////////////////////////////// // the rate we run the main loop at @@ -306,7 +306,7 @@ static AP_SteerController steerController(ahrs); 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); #if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL SITL sitl; diff --git a/APMrover2/defines.h b/APMrover2/defines.h index e01c049397..3657184934 100644 --- a/APMrover2/defines.h +++ b/APMrover2/defines.h @@ -143,12 +143,9 @@ enum mode { // EEPROM addresses -#define EEPROM_MAX_ADDR 4096 -// parameters get the first 1KiB 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 MAX_WAYPOINTS ((EEPROM_MAX_ADDR - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe +// parameters get the first 1KiB of EEPROM, remainder is for mission commands +#define MISSION_START_BYTE 0x500 +#define MISSION_END_BYTE HAL_STORAGE_SIZE_AVAILABLE // convert a boolean (0 or 1) to a sign for multiplying (0 maps to 1, 1 maps to -1) #define BOOL_TO_SIGN(bvalue) ((bvalue)?-1:1) diff --git a/APMrover2/setup.pde b/APMrover2/setup.pde index 32df9d22fc..f4e395d5c5 100644 --- a/APMrover2/setup.pde +++ b/APMrover2/setup.pde @@ -654,7 +654,7 @@ static void zero_eeprom(void) { uint8_t b = 0; cliSerial->printf_P(PSTR("\nErasing EEPROM\n")); - for (uint16_t i = 0; i < EEPROM_MAX_ADDR; i++) { + for (uint16_t i = 0; i < HAL_STORAGE_SIZE_AVAILABLE; i++) { hal.storage->write_byte(i, b); } cliSerial->printf_P(PSTR("done\n"));