mirror of https://github.com/ArduPilot/ardupilot
Rover: Reset all storage when format version is incorrect
This commit is contained in:
parent
58895b5a82
commit
d920795537
|
@ -761,6 +761,7 @@ void Rover::load_parameters(void)
|
|||
g.format_version != Parameters::k_format_version) {
|
||||
// erase all parameters
|
||||
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||
StorageManager::erase();
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
|
|
Loading…
Reference in New Issue