mirror of https://github.com/ArduPilot/ardupilot
DataFlash : Removed Chip Erase - relying on Block erase only
This commit is contained in:
parent
44b715af9b
commit
a6b874b591
|
@ -189,31 +189,10 @@ uint16_t DataFlash_Class::GetFilePage()
|
|||
|
||||
void DataFlash_Class::EraseAll(void (*delay_cb)(unsigned long))
|
||||
{
|
||||
// write a bad value to the last page
|
||||
StartWrite(df_NumPages+1);
|
||||
WriteLong(DF_LOGGING_FORMAT_INVALID);
|
||||
BufferToPage(df_BufferNum,df_PageAdr,1);
|
||||
|
||||
ChipErase(delay_cb);
|
||||
SetFileNumber(0xFFFF);
|
||||
|
||||
StartRead(0);
|
||||
StartRead(df_NumPages+1);
|
||||
int32_t format = ReadLong();
|
||||
|
||||
// if (format == DF_LOGGING_FORMAT_INVALID)
|
||||
// the current method for checking if chip erase worked is producing false positives
|
||||
// we are forcing the block erase until we have a deterministic test method
|
||||
{
|
||||
// the chip erase didn't work - fall back to a erasing
|
||||
// each page separately. The errata on the APM2 dataflash chip
|
||||
// suggests that chip erase won't always work
|
||||
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
||||
BlockErase(j);
|
||||
delay_cb(1);
|
||||
}
|
||||
}
|
||||
|
||||
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
|
||||
BlockErase(j);
|
||||
delay_cb(1);
|
||||
}
|
||||
// write the logging format in the last page
|
||||
StartWrite(df_NumPages+1);
|
||||
WriteLong(DF_LOGGING_FORMAT);
|
||||
|
|
Loading…
Reference in New Issue