mirror of https://github.com/ArduPilot/ardupilot
Plane: Reset all storage when format version is incorrect
This commit is contained in:
parent
6613c678a0
commit
ae6dc01cd5
|
@ -1291,6 +1291,7 @@ void Plane::load_parameters(void)
|
||||||
|
|
||||||
// erase all parameters
|
// erase all parameters
|
||||||
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||||
|
StorageManager::erase();
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
|
||||||
// save the current format version
|
// save the current format version
|
||||||
|
|
Loading…
Reference in New Issue