Mission: add init and check_eeprom_version methods

This commit is contained in:
Randy Mackay 2014-03-11 12:52:23 +09:00
parent 923dca0cb8
commit ddc4cd4f18
2 changed files with 32 additions and 1 deletions

View File

@ -24,6 +24,14 @@ extern const AP_HAL::HAL& hal;
/// public mission methods
///
/// init - initialises this library including checks the version in eeprom matches this library
void AP_Mission::init()
{
// check_eeprom_version - checks version of missions stored in eeprom matches this library
// command list will be cleared if they do not match
check_eeprom_version();
}
/// start - resets current commands to point to the beginning of the mission
/// To-Do: should we validate the mission first and return true/false?
void AP_Mission::start()
@ -1033,3 +1041,17 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd)
// To-Do: log an error
return;
}
// check_eeprom_version - checks version of missions stored in eeprom matches this library
// command list will be cleared if they do not match
void AP_Mission::check_eeprom_version()
{
uint32_t eeprom_version = hal.storage->read_dword(AP_MISSION_EEPROM_VERSION_ADDR);
// if eeprom version does not match, clear the command list and update the eeprom version
if (eeprom_version != AP_MISSION_EEPROM_VERSION) {
if (clear()) {
hal.storage->write_dword(AP_MISSION_EEPROM_VERSION_ADDR, AP_MISSION_EEPROM_VERSION);
}
}
}

View File

@ -23,8 +23,10 @@
#include <AP_HAL.h>
// definitions
#define AP_MISSION_EEPROM_VERSION 0x65AD // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
#define AP_MISSION_EEPROM_MAX_ADDR 4096 // parameters get the first 1536 bytes of EEPROM, remainder is for waypoints
#define AP_MISSION_EEPROM_START_BYTE 0x600 // where in memory home WP is stored, all mission commands appear afterthis
#define AP_MISSION_EEPROM_VERSION_ADDR 0x600 // where version number is stored in eeprom
#define AP_MISSION_EEPROM_START_BYTE 0x604 // where in memory home WP is stored, all mission commands appear after this
#define AP_MISSION_EEPROM_COMMAND_SIZE 15 // size in bytes of all mission commands
#define AP_MISSION_FENCEPOINTS_MAX 6 // we reserve space for 6 fence points at the end of EEPROM although this is not currently implemented
#define AP_MISSION_FENCEPOINTS_SIZE sizeof(Vector2l) // each fence points size in eeprom
@ -104,6 +106,9 @@ public:
/// public mission methods
///
/// init - initialises this library including checks the version in eeprom matches this library
void init();
/// status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped
mission_state state() const { return _flags.state; }
@ -240,6 +245,10 @@ private:
/// increment_jump_times_run - increments the recorded number of times the jump command has been run
void increment_jump_times_run(Mission_Command& cmd);
/// check_eeprom_version - checks version of missions stored in eeprom matches this library
/// command list will be cleared if they do not match
void check_eeprom_version();
// references to external libraries
const AP_AHRS& _ahrs; // used only for home position