mirror of https://github.com/ArduPilot/ardupilot
AP_Param: support restoring from parameter backup region
if header on primary parameter storage is corrupt then restore from backup
This commit is contained in:
parent
03a033c5c4
commit
4d58bcb321
|
@ -32,6 +32,7 @@
|
|||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_InternalError/AP_InternalError.h>
|
||||
#include <stdio.h>
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include <SITL/SITL.h>
|
||||
|
@ -110,6 +111,9 @@ const AP_Param::param_defaults_struct AP_Param::param_defaults_data = {
|
|||
// storage object
|
||||
StorageAccess AP_Param::_storage(StorageManager::StorageParam);
|
||||
|
||||
// backup storage object
|
||||
StorageAccess AP_Param::_storage_bak(StorageManager::StorageParamBak);
|
||||
|
||||
// flags indicating frame type
|
||||
uint16_t AP_Param::_frame_type_flags;
|
||||
|
||||
|
@ -117,6 +121,7 @@ uint16_t AP_Param::_frame_type_flags;
|
|||
void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
|
||||
{
|
||||
_storage.write_block(ofs, ptr, size);
|
||||
_storage_bak.write_block(ofs, ptr, size);
|
||||
}
|
||||
|
||||
bool AP_Param::_hide_disabled_groups = true;
|
||||
|
@ -323,19 +328,32 @@ bool AP_Param::check_var_info(void)
|
|||
// setup the _var_info[] table
|
||||
bool AP_Param::setup(void)
|
||||
{
|
||||
struct EEPROM_header hdr;
|
||||
struct EEPROM_header hdr {};
|
||||
struct EEPROM_header hdr2 {};
|
||||
|
||||
// check the header
|
||||
_storage.read_block(&hdr, 0, sizeof(hdr));
|
||||
_storage_bak.read_block(&hdr2, 0, sizeof(hdr2));
|
||||
if (hdr.magic[0] != k_EEPROM_magic0 ||
|
||||
hdr.magic[1] != k_EEPROM_magic1 ||
|
||||
hdr.revision != k_EEPROM_revision) {
|
||||
if (hdr2.magic[0] == k_EEPROM_magic0 &&
|
||||
hdr2.magic[1] == k_EEPROM_magic1 &&
|
||||
hdr2.revision == k_EEPROM_revision &&
|
||||
_storage.copy_area(_storage_bak)) {
|
||||
// restored from backup
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::params_restored);
|
||||
return true;
|
||||
}
|
||||
// header doesn't match. We can't recover any variables. Wipe
|
||||
// the header and setup the sentinal directly after the header
|
||||
Debug("bad header in setup - erasing");
|
||||
erase_all();
|
||||
}
|
||||
|
||||
// ensure that backup is in sync with primary
|
||||
_storage_bak.copy_area(_storage);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -678,6 +678,7 @@ private:
|
|||
void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;
|
||||
|
||||
static StorageAccess _storage;
|
||||
static StorageAccess _storage_bak;
|
||||
static uint16_t _num_vars;
|
||||
static uint16_t _parameter_count;
|
||||
static uint16_t _count_marker;
|
||||
|
|
Loading…
Reference in New Issue