Rover: convert to using StorageManager
This commit is contained in:
parent
e260f1c569
commit
c150338e53
@ -62,6 +62,7 @@
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Menu.h>
|
||||
#include <AP_Param.h>
|
||||
#include <StorageManager.h>
|
||||
#include <AP_GPS.h> // ArduPilot GPS library
|
||||
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
|
||||
#include <AP_ADC_AnalogSource.h>
|
||||
@ -130,7 +131,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, MISSION_START_BYTE);
|
||||
AP_Param param_loader(var_info);
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// the rate we run the main loop at
|
||||
@ -273,7 +274,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, MISSION_START_BYTE, MISSION_END_BYTE);
|
||||
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
SITL sitl;
|
||||
|
@ -126,12 +126,6 @@ enum mode {
|
||||
|
||||
#define SPEEDFILT 400 // centimeters/second; the speed below which a groundstart will be triggered
|
||||
|
||||
|
||||
// EEPROM addresses
|
||||
// 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)
|
||||
|
||||
|
@ -654,9 +654,7 @@ static void zero_eeprom(void)
|
||||
{
|
||||
uint8_t b = 0;
|
||||
cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
|
||||
for (uint16_t i = 0; i < HAL_STORAGE_SIZE_AVAILABLE; i++) {
|
||||
hal.storage->write_byte(i, b);
|
||||
}
|
||||
StorageManager::erase();
|
||||
cliSerial->printf_P(PSTR("done\n"));
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user