|
|
|
@ -27,6 +27,9 @@ const AP_Param::GroupInfo AP_Mission::var_info[] PROGMEM = {
@@ -27,6 +27,9 @@ const AP_Param::GroupInfo AP_Mission::var_info[] PROGMEM = {
|
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
|
// storage object
|
|
|
|
|
StorageAccess AP_Mission::_storage(StorageManager::StorageMission); |
|
|
|
|
|
|
|
|
|
///
|
|
|
|
|
/// public mission methods
|
|
|
|
|
///
|
|
|
|
@ -377,8 +380,6 @@ bool AP_Mission::set_current_cmd(uint16_t index)
@@ -377,8 +380,6 @@ bool AP_Mission::set_current_cmd(uint16_t index)
|
|
|
|
|
/// true is return if successful
|
|
|
|
|
bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const |
|
|
|
|
{ |
|
|
|
|
uint16_t pos_in_storage; // position in storage from where we will read the next byte
|
|
|
|
|
|
|
|
|
|
// exit immediately if index is beyond last command but we always let cmd #0 (i.e. home) be read
|
|
|
|
|
if (index > (unsigned)_cmd_total && index != 0) { |
|
|
|
|
return false; |
|
|
|
@ -394,11 +395,11 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
@@ -394,11 +395,11 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
|
|
|
|
|
// Find out proper location in memory by using the start_byte position + the index
|
|
|
|
|
// we can load a command, we don't process it yet
|
|
|
|
|
// read WP position
|
|
|
|
|
pos_in_storage = _storage_start + 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE); |
|
|
|
|
uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE); |
|
|
|
|
|
|
|
|
|
cmd.id = hal.storage->read_byte(pos_in_storage); |
|
|
|
|
cmd.p1 = hal.storage->read_word(pos_in_storage+1); |
|
|
|
|
hal.storage->read_block(cmd.content.bytes, pos_in_storage+3, 12); |
|
|
|
|
cmd.id = _storage.read_byte(pos_in_storage); |
|
|
|
|
cmd.p1 = _storage.read_uint16(pos_in_storage+1); |
|
|
|
|
_storage.read_block(cmd.content.bytes, pos_in_storage+3, 12); |
|
|
|
|
|
|
|
|
|
// set command's index to it's position in eeprom
|
|
|
|
|
cmd.index = index; |
|
|
|
@ -414,16 +415,16 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
@@ -414,16 +415,16 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
|
|
|
|
|
bool AP_Mission::write_cmd_to_storage(uint16_t index, Mission_Command& cmd) |
|
|
|
|
{ |
|
|
|
|
// range check cmd's index
|
|
|
|
|
if (index >= _cmd_total_max) { |
|
|
|
|
if (index >= num_commands_max()) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// calculate where in storage the command should be placed
|
|
|
|
|
uint16_t pos_in_storage = _storage_start + 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE); |
|
|
|
|
uint16_t pos_in_storage = 4 + (index * AP_MISSION_EEPROM_COMMAND_SIZE); |
|
|
|
|
|
|
|
|
|
hal.storage->write_byte(pos_in_storage, cmd.id); |
|
|
|
|
hal.storage->write_word(pos_in_storage+1, cmd.p1); |
|
|
|
|
hal.storage->write_block(pos_in_storage+3, cmd.content.bytes, 12); |
|
|
|
|
_storage.write_byte(pos_in_storage, cmd.id); |
|
|
|
|
_storage.write_uint16(pos_in_storage+1, cmd.p1); |
|
|
|
|
_storage.write_block(pos_in_storage+3, cmd.content.bytes, 12); |
|
|
|
|
|
|
|
|
|
// remember when the mission last changed
|
|
|
|
|
_last_change_time_ms = hal.scheduler->millis(); |
|
|
|
@ -1193,12 +1194,22 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd)
@@ -1193,12 +1194,22 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd)
|
|
|
|
|
// command list will be cleared if they do not match
|
|
|
|
|
void AP_Mission::check_eeprom_version() |
|
|
|
|
{ |
|
|
|
|
uint32_t eeprom_version = hal.storage->read_dword(_storage_start); |
|
|
|
|
uint32_t eeprom_version = _storage.read_uint32(0); |
|
|
|
|
|
|
|
|
|
// 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(_storage_start, AP_MISSION_EEPROM_VERSION); |
|
|
|
|
_storage.write_uint32(0, AP_MISSION_EEPROM_VERSION); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
return total number of commands that can fit in storage space |
|
|
|
|
*/ |
|
|
|
|
uint16_t AP_Mission::num_commands_max(void) const |
|
|
|
|
{ |
|
|
|
|
// -4 to remove space for eeprom version number
|
|
|
|
|
return (_storage.size() - 4) / AP_MISSION_EEPROM_COMMAND_SIZE; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|