Add DataFlash.Init before doing a forced log erase on eeprom reset.

Add progress indication during log erase
This commit is contained in:
Doug Weibel 2011-11-28 19:42:27 -07:00
parent b4a0d8a275
commit b03de3095e
4 changed files with 23 additions and 20 deletions

View File

@ -136,6 +136,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
for(int j = 1; j <= DF_LAST_PAGE; j++) {
DataFlash.PageErase(j);
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
if(j%128 == 0) Serial.printf_P(PSTR("+"));
}
g.log_last_filenumber.set_and_save(0);

View File

@ -164,6 +164,12 @@ static void init_ardupilot()
delay(100); // wait for serial send
AP_Var::erase_all();
// erase DataFlash on format version change
#if LOGGING_ENABLED == ENABLED
DataFlash.Init();
erase_logs(NULL, NULL);
#endif
// clear logs - createing infinate lockup
//erase_logs(NULL, NULL);

View File

@ -140,6 +140,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
for(int j = 1; j <= DF_LAST_PAGE; j++) {
DataFlash.PageErase(j);
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
if(j%128 == 0) Serial.printf_P(PSTR("+"));
}
g.log_last_filenumber.set_and_save(0);

View File

@ -116,31 +116,26 @@ static void init_ardupilot()
//
// Check the EEPROM format version before loading any parameters from EEPROM.
//
if (!g.format_version.load()) {
Serial.println_P(PSTR("\nEEPROM blank - resetting all parameters to defaults...\n"));
delay(100); // wait for serial msg to flush
if (!g.format_version.load() ||
g.format_version != Parameters::k_format_version) {
// erase all parameters
Serial.printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
delay(100); // wait for serial send
AP_Var::erase_all();
// erase DataFlash on format version change
#if LOGGING_ENABLED == ENABLED
DataFlash.Init();
erase_logs(NULL, NULL);
#endif
// save the current format version
g.format_version.set_and_save(Parameters::k_format_version);
} else if (g.format_version != Parameters::k_format_version) {
Serial.printf_P(PSTR("\n\nEEPROM format version %d not compatible with this firmware (requires %d)"
"\n\nForcing complete parameter reset..."),
g.format_version.get(), Parameters::k_format_version);
delay(100); // wait for serial msg to flush
// erase all parameters
AP_Var::erase_all();
// save the new format version
g.format_version.set_and_save(Parameters::k_format_version);
Serial.println_P(PSTR("done."));
} else {
} else {
unsigned long before = micros();
// Load all auto-loaded EEPROM variables
AP_Var::load_all();