Browse Source

Rover: Reset all storage when format version is incorrect

mission-4.1.18
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
d920795537
  1. 1
      APMrover2/Parameters.cpp

1
APMrover2/Parameters.cpp

@ -761,6 +761,7 @@ void Rover::load_parameters(void) @@ -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…
Cancel
Save