DataFlash: fallback to BlockErase if ChipErase fails

The errata on the APM2 dataflash chip says that ChipErase may not work
on some chips
This commit is contained in:
Andrew Tridgell 2012-07-04 12:36:42 +10:00
parent 5623ef99a0
commit c6ff292721
6 changed files with 77 additions and 0 deletions

View File

@ -3,6 +3,7 @@
DataFlash.cpp - DataFlash log library generic code
*/
#include <FastSerial.h>
#include <stdint.h>
#include "DataFlash.h"
@ -188,8 +189,28 @@ 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 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);
}
}
// write the logging format in the last page
StartWrite(df_NumPages+1);
WriteLong(DF_LOGGING_FORMAT);

View File

@ -12,6 +12,9 @@
// this if (and only if!) the low level format changes
#define DF_LOGGING_FORMAT 0x28122011
// we use an invalie logging format to test the chip erase
#define DF_LOGGING_FORMAT_INVALID 0x28122012
class DataFlash_Class
{
private:
@ -32,6 +35,7 @@ class DataFlash_Class
virtual void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr) = 0;
virtual unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr) = 0;
virtual void PageErase(uint16_t PageAdr) = 0;
virtual void BlockErase(uint16_t BlockAdr) = 0;
virtual void ChipErase(void (*delay_cb)(unsigned long)) = 0;
// internal high level functions

View File

@ -294,6 +294,29 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
}
void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
{
dataflash_CS_active(); // activate dataflash command decoder
SPI.transfer(DF_BLOCK_ERASE); // Command
if (df_PageSize==512) {
SPI.transfer((unsigned char)(BlockAdr >> 3));
SPI.transfer((unsigned char)(BlockAdr << 5));
} else {
SPI.transfer((unsigned char)(BlockAdr >> 4));
SPI.transfer((unsigned char)(BlockAdr << 4));
}
SPI.transfer(0x00); // "dont cares"
dataflash_CS_inactive(); //initiate flash page erase
dataflash_CS_active();
while(!ReadStatus());
dataflash_CS_inactive(); // deactivate dataflash command decoder
}
void DataFlash_APM1::ChipErase(void (*delay_cb)(unsigned long))
{

View File

@ -19,6 +19,7 @@ class DataFlash_APM1 : public DataFlash_Class
unsigned char ReadStatus();
uint16_t PageSize();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase(void (*delay_cb)(unsigned long));
public:

View File

@ -349,6 +349,33 @@ void DataFlash_APM2::PageErase (uint16_t PageAdr)
CS_inactive();
}
// erase a block of 8 pages.
void DataFlash_APM2::BlockErase(uint16_t BlockAdr)
{
// activate dataflash command decoder
CS_active();
// Send block erase command
SPI_transfer(DF_BLOCK_ERASE);
if (df_PageSize==512) {
SPI_transfer((unsigned char)(BlockAdr >> 3));
SPI_transfer((unsigned char)(BlockAdr << 5));
} else {
SPI_transfer((unsigned char)(BlockAdr >> 4));
SPI_transfer((unsigned char)(BlockAdr << 4));
}
SPI_transfer(0x00);
//initiate flash page erase
CS_inactive();
CS_active();
while(!ReadStatus());
// release SPI bus for use by other sensors
CS_inactive();
}
void DataFlash_APM2::ChipErase(void (*delay_cb)(unsigned long))
{

View File

@ -23,6 +23,7 @@ class DataFlash_APM2 : public DataFlash_Class
void CS_inactive();
void CS_active();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase(void (*delay_cb)(unsigned long));
public: