mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: move parameter storage formatting up to AP_Vehicle
This commit is contained in:
parent
c864047c1f
commit
222fe57915
|
@ -287,6 +287,8 @@ protected:
|
|||
|
||||
virtual void init_ardupilot() = 0;
|
||||
virtual void load_parameters() = 0;
|
||||
void load_parameters(AP_Int16 &format_version, const uint16_t expected_format_version);
|
||||
|
||||
virtual void set_control_channels() {}
|
||||
|
||||
// board specific config
|
||||
|
|
|
@ -0,0 +1,24 @@
|
|||
#include "AP_Vehicle.h"
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <StorageManager/StorageManager.h>
|
||||
|
||||
void AP_Vehicle::load_parameters(AP_Int16 &format_version, const uint16_t expected_format_version)
|
||||
{
|
||||
if (!format_version.load() ||
|
||||
format_version != expected_format_version) {
|
||||
|
||||
// erase all parameters
|
||||
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||
StorageManager::erase();
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
format_version.set_and_save(expected_format_version);
|
||||
hal.console->printf("done.\n");
|
||||
}
|
||||
format_version.set_default(expected_format_version);
|
||||
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
}
|
Loading…
Reference in New Issue