dataflash: reworked classes to move most code to parent class
this moves all the non-hardware specific code to the parent DataFlash_Class class, keeping the hw specific code much smaller and simpler. This should prevent discrepancies creeping in between APM1 and APM2 support again
This commit is contained in:
parent
d81dc21dfe
commit
977326e991
@ -10,32 +10,57 @@
|
||||
|
||||
class DataFlash_Class
|
||||
{
|
||||
private:
|
||||
// DataFlash Log variables...
|
||||
unsigned char df_BufferNum;
|
||||
unsigned char df_Read_BufferNum;
|
||||
uint16_t df_BufferIdx;
|
||||
uint16_t df_Read_BufferIdx;
|
||||
uint16_t df_PageAdr;
|
||||
uint16_t df_Read_PageAdr;
|
||||
unsigned char df_Stop_Write;
|
||||
uint16_t df_FileNumber;
|
||||
uint16_t df_FilePage;
|
||||
|
||||
virtual void WaitReady() = 0;
|
||||
virtual void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data) = 0;
|
||||
virtual void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait) = 0;
|
||||
virtual void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr) = 0;
|
||||
virtual unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr) = 0;
|
||||
|
||||
public:
|
||||
unsigned char df_manufacturer;
|
||||
unsigned char df_device_0;
|
||||
unsigned char df_device_1;
|
||||
|
||||
DataFlash_Class() {} // Constructor
|
||||
|
||||
virtual void Init() = 0;
|
||||
virtual void Init(void) = 0;
|
||||
virtual void ReadManufacturerID() = 0;
|
||||
virtual int16_t GetPage() = 0;
|
||||
virtual int16_t GetWritePage() = 0;
|
||||
virtual void PageErase (uint16_t PageAdr) = 0;
|
||||
virtual void ChipErase () = 0;
|
||||
int16_t GetPage(void);
|
||||
int16_t GetWritePage(void);
|
||||
virtual void PageErase(uint16_t PageAdr) = 0;
|
||||
virtual void ChipErase(void) = 0;
|
||||
|
||||
// Write methods
|
||||
virtual void StartWrite(int16_t PageAdr) = 0;
|
||||
virtual void FinishWrite() = 0;
|
||||
virtual void WriteByte(unsigned char data) = 0;
|
||||
virtual void WriteInt(int16_t data) = 0;
|
||||
virtual void WriteLong(int32_t data) = 0;
|
||||
void StartWrite(int16_t PageAdr);
|
||||
void FinishWrite(void);
|
||||
void WriteByte(unsigned char data);
|
||||
void WriteInt(int16_t data);
|
||||
void WriteLong(int32_t data);
|
||||
|
||||
// Read methods
|
||||
virtual void StartRead(int16_t PageAdr) = 0;
|
||||
virtual unsigned char ReadByte() = 0;
|
||||
virtual int16_t ReadInt() = 0;
|
||||
virtual int32_t ReadLong() = 0;
|
||||
void StartRead(int16_t PageAdr);
|
||||
unsigned char ReadByte();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
|
||||
void SetFileNumber(uint16_t FileNumber);
|
||||
uint16_t GetFileNumber();
|
||||
uint16_t GetFilePage();
|
||||
|
||||
uint16_t df_PageSize;
|
||||
uint16_t df_NumPages;
|
||||
};
|
||||
|
||||
#include "DataFlash_APM1.h"
|
||||
|
@ -105,8 +105,6 @@ void DataFlash_APM1::Init(void)
|
||||
digitalWrite(DF_RESET,HIGH);
|
||||
#endif
|
||||
|
||||
df_Read_END=false;
|
||||
|
||||
dataflash_CS_inactive(); //disable device
|
||||
|
||||
// Setup SPI Master, Mode 3, fosc/4 = 4MHz
|
||||
@ -305,185 +303,3 @@ void DataFlash_APM1::ChipErase ()
|
||||
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
||||
}
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_APM1::StartWrite(int16_t PageAdr)
|
||||
{
|
||||
df_BufferNum=1;
|
||||
df_BufferIdx=4;
|
||||
df_PageAdr=PageAdr;
|
||||
df_Stop_Write=0;
|
||||
WaitReady();
|
||||
// We are starting a new page - write FileNumber and FilePage
|
||||
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
|
||||
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
|
||||
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
|
||||
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_APM1::FinishWrite(void)
|
||||
{
|
||||
df_BufferIdx=0;
|
||||
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
|
||||
df_PageAdr++;
|
||||
if (DF_OVERWRITE_DATA==1)
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
df_PageAdr = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
|
||||
df_Stop_Write=1;
|
||||
}
|
||||
|
||||
if (df_BufferNum==1) // Change buffer to continue writing...
|
||||
df_BufferNum=2;
|
||||
else
|
||||
df_BufferNum=1;
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_APM1::WriteByte(byte data)
|
||||
{
|
||||
if (!df_Stop_Write)
|
||||
{
|
||||
BufferWrite(df_BufferNum,df_BufferIdx,data);
|
||||
df_BufferIdx++;
|
||||
if (df_BufferIdx >= df_PageSize) // End of buffer?
|
||||
{
|
||||
df_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
|
||||
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
|
||||
df_PageAdr++;
|
||||
if (DF_OVERWRITE_DATA==1)
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
df_PageAdr = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
|
||||
df_Stop_Write=1;
|
||||
}
|
||||
|
||||
if (df_BufferNum==1) // Change buffer to continue writing...
|
||||
df_BufferNum=2;
|
||||
else
|
||||
df_BufferNum=1;
|
||||
// We are starting a new page - write FileNumber and FilePage
|
||||
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
|
||||
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
|
||||
df_FilePage++;
|
||||
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
|
||||
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void DataFlash_APM1::WriteInt(int16_t data)
|
||||
{
|
||||
WriteByte(data>>8); // High byte
|
||||
WriteByte(data&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_APM1::WriteLong(int32_t data)
|
||||
{
|
||||
WriteByte(data>>24); // First byte
|
||||
WriteByte(data>>16);
|
||||
WriteByte(data>>8);
|
||||
WriteByte(data&0xFF); // Last byte
|
||||
}
|
||||
|
||||
// Get the last page written to
|
||||
int16_t DataFlash_APM1::GetWritePage()
|
||||
{
|
||||
return(df_PageAdr);
|
||||
}
|
||||
|
||||
// Get the last page read
|
||||
int16_t DataFlash_APM1::GetPage()
|
||||
{
|
||||
return(df_Read_PageAdr-1);
|
||||
}
|
||||
|
||||
void DataFlash_APM1::StartRead(int16_t PageAdr)
|
||||
{
|
||||
df_Read_BufferNum=1;
|
||||
df_Read_BufferIdx=4;
|
||||
df_Read_PageAdr=PageAdr;
|
||||
WaitReady();
|
||||
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer
|
||||
//Serial.print(df_Read_PageAdr, DEC); Serial.print("\t");
|
||||
df_Read_PageAdr++;
|
||||
|
||||
// We are starting a new page - read FileNumber and FilePage
|
||||
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
|
||||
//Serial.print(df_FileNumber, DEC); Serial.print("\t");
|
||||
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
|
||||
//Serial.println(df_FileNumber, DEC); Serial.print("\t");
|
||||
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
|
||||
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
|
||||
}
|
||||
|
||||
byte DataFlash_APM1::ReadByte()
|
||||
{
|
||||
byte result;
|
||||
|
||||
WaitReady();
|
||||
result = BufferRead(df_Read_BufferNum,df_Read_BufferIdx);
|
||||
df_Read_BufferIdx++;
|
||||
if (df_Read_BufferIdx >= df_PageSize) // End of buffer?
|
||||
{
|
||||
df_Read_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
|
||||
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer
|
||||
df_Read_PageAdr++;
|
||||
if (df_Read_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
{
|
||||
df_Read_PageAdr = 0;
|
||||
df_Read_END = true;
|
||||
}
|
||||
|
||||
// We are starting a new page - read FileNumber and FilePage
|
||||
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
|
||||
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
|
||||
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
|
||||
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
int16_t DataFlash_APM1::ReadInt()
|
||||
{
|
||||
uint16_t result;
|
||||
|
||||
result = ReadByte(); // High byte
|
||||
result = (result<<8) | ReadByte(); // Low byte
|
||||
return (int16_t)result;
|
||||
}
|
||||
|
||||
int32_t DataFlash_APM1::ReadLong()
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
result = ReadByte(); // First byte
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte(); // Last byte
|
||||
return (int32_t)result;
|
||||
}
|
||||
|
||||
void DataFlash_APM1::SetFileNumber(uint16_t FileNumber)
|
||||
{
|
||||
df_FileNumber = FileNumber;
|
||||
df_FilePage = 1;
|
||||
}
|
||||
|
||||
uint16_t DataFlash_APM1::GetFileNumber()
|
||||
{
|
||||
return df_FileNumber;
|
||||
}
|
||||
|
||||
uint16_t DataFlash_APM1::GetFilePage()
|
||||
{
|
||||
return df_FilePage;
|
||||
}
|
||||
|
||||
|
@ -9,17 +9,6 @@
|
||||
class DataFlash_APM1 : public DataFlash_Class
|
||||
{
|
||||
private:
|
||||
// DataFlash Log variables...
|
||||
unsigned char df_BufferNum;
|
||||
unsigned char df_Read_BufferNum;
|
||||
uint16_t df_BufferIdx;
|
||||
uint16_t df_Read_BufferIdx;
|
||||
uint16_t df_PageAdr;
|
||||
uint16_t df_Read_PageAdr;
|
||||
unsigned char df_Read_END;
|
||||
unsigned char df_Stop_Write;
|
||||
uint16_t df_FileNumber;
|
||||
uint16_t df_FilePage;
|
||||
//Methods
|
||||
unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr);
|
||||
void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data);
|
||||
@ -31,35 +20,12 @@ class DataFlash_APM1 : public DataFlash_Class
|
||||
uint16_t PageSize();
|
||||
|
||||
public:
|
||||
unsigned char df_manufacturer;
|
||||
unsigned char df_device_0;
|
||||
unsigned char df_device_1;
|
||||
uint16_t df_PageSize;
|
||||
uint16_t df_NumPages;
|
||||
|
||||
DataFlash_APM1(); // Constructor
|
||||
void Init();
|
||||
void ReadManufacturerID();
|
||||
int16_t GetPage();
|
||||
int16_t GetWritePage();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
// Write methods
|
||||
void StartWrite(int16_t PageAdr);
|
||||
void FinishWrite();
|
||||
void WriteByte(unsigned char data);
|
||||
void WriteInt(int16_t data);
|
||||
void WriteLong(int32_t data);
|
||||
|
||||
// Read methods
|
||||
void StartRead(int16_t PageAdr);
|
||||
unsigned char ReadByte();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
|
||||
void SetFileNumber(uint16_t FileNumber);
|
||||
uint16_t GetFileNumber();
|
||||
uint16_t GetFilePage();
|
||||
};
|
||||
|
||||
#endif // __DATAFLASH_APM1_H__
|
||||
|
@ -118,8 +118,6 @@ void DataFlash_APM2::Init(void)
|
||||
delay(1);
|
||||
digitalWrite(DF_RESET,HIGH);
|
||||
|
||||
df_Read_END=false;
|
||||
|
||||
CS_inactive(); //disable device
|
||||
|
||||
// Setup Serial Port3 in SPI mode (MSPI), Mode 0, Clock: 8Mhz
|
||||
@ -312,184 +310,3 @@ void DataFlash_APM2::ChipErase ()
|
||||
CS_active();
|
||||
while(!ReadStatus());
|
||||
}
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_APM2::StartWrite(int16_t PageAdr)
|
||||
{
|
||||
df_BufferNum=1;
|
||||
df_BufferIdx=4;
|
||||
df_PageAdr=PageAdr;
|
||||
df_Stop_Write=0;
|
||||
WaitReady();
|
||||
|
||||
// We are starting a new page - write FileNumber and FilePage
|
||||
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
|
||||
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
|
||||
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
|
||||
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_APM2::FinishWrite(void)
|
||||
{
|
||||
df_BufferIdx=0;
|
||||
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
|
||||
df_PageAdr++;
|
||||
if (DF_OVERWRITE_DATA==1)
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
df_PageAdr = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
|
||||
df_Stop_Write=1;
|
||||
}
|
||||
|
||||
if (df_BufferNum==1) // Change buffer to continue writing...
|
||||
df_BufferNum=2;
|
||||
else
|
||||
df_BufferNum=1;
|
||||
}
|
||||
|
||||
|
||||
void DataFlash_APM2::WriteByte(byte data)
|
||||
{
|
||||
if (!df_Stop_Write)
|
||||
{
|
||||
BufferWrite(df_BufferNum,df_BufferIdx,data);
|
||||
df_BufferIdx++;
|
||||
if (df_BufferIdx >= df_PageSize) // End of buffer?
|
||||
{
|
||||
df_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
|
||||
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
|
||||
df_PageAdr++;
|
||||
if (DF_OVERWRITE_DATA==1)
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
df_PageAdr = 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (df_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, stop here
|
||||
df_Stop_Write=1;
|
||||
}
|
||||
|
||||
if (df_BufferNum==1) // Change buffer to continue writing...
|
||||
df_BufferNum=2;
|
||||
else
|
||||
df_BufferNum=1;
|
||||
// We are starting a new page - write FileNumber and FilePage
|
||||
BufferWrite(df_BufferNum,0,df_FileNumber>>8); // High byte
|
||||
BufferWrite(df_BufferNum,1,df_FileNumber&0xFF); // Low byte
|
||||
df_FilePage++;
|
||||
BufferWrite(df_BufferNum,2,df_FilePage>>8); // High byte
|
||||
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void DataFlash_APM2::WriteInt(int16_t data)
|
||||
{
|
||||
WriteByte(data>>8); // High byte
|
||||
WriteByte(data&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_APM2::WriteLong(int32_t data)
|
||||
{
|
||||
WriteByte(data>>24); // First byte
|
||||
WriteByte(data>>16);
|
||||
WriteByte(data>>8);
|
||||
WriteByte(data&0xFF); // Last byte
|
||||
}
|
||||
|
||||
// Get the last page written to
|
||||
int16_t DataFlash_APM2::GetWritePage()
|
||||
{
|
||||
return(df_PageAdr);
|
||||
}
|
||||
|
||||
// Get the last page read
|
||||
int16_t DataFlash_APM2::GetPage()
|
||||
{
|
||||
return(df_Read_PageAdr-1);
|
||||
}
|
||||
|
||||
void DataFlash_APM2::StartRead(int16_t PageAdr)
|
||||
{
|
||||
df_Read_BufferNum=1;
|
||||
df_Read_BufferIdx=4;
|
||||
df_Read_PageAdr=PageAdr;
|
||||
WaitReady();
|
||||
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer
|
||||
df_Read_PageAdr++;
|
||||
|
||||
// We are starting a new page - read FileNumber and FilePage
|
||||
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
|
||||
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
|
||||
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
|
||||
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
|
||||
}
|
||||
|
||||
byte DataFlash_APM2::ReadByte()
|
||||
{
|
||||
byte result;
|
||||
|
||||
WaitReady();
|
||||
result = BufferRead(df_Read_BufferNum,df_Read_BufferIdx);
|
||||
|
||||
df_Read_BufferIdx++;
|
||||
if (df_Read_BufferIdx >= df_PageSize) // End of buffer?
|
||||
{
|
||||
df_Read_BufferIdx=4; //(4 bytes for FileNumber, FilePage)
|
||||
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer
|
||||
df_Read_PageAdr++;
|
||||
if (df_Read_PageAdr>DF_LAST_PAGE) // If we reach the end of the memory, start from the begining
|
||||
{
|
||||
df_Read_PageAdr = 0;
|
||||
df_Read_END = true;
|
||||
}
|
||||
|
||||
// We are starting a new page - read FileNumber and FilePage
|
||||
df_FileNumber = BufferRead(df_Read_BufferNum,0); // High byte
|
||||
df_FileNumber = (df_FileNumber<<8) | BufferRead(df_Read_BufferNum,1); // Low byte
|
||||
df_FilePage = BufferRead(df_Read_BufferNum,2); // High byte
|
||||
df_FilePage = (df_FilePage<<8) | BufferRead(df_Read_BufferNum,3); // Low byte
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
int16_t DataFlash_APM2::ReadInt()
|
||||
{
|
||||
uint16_t result;
|
||||
|
||||
result = ReadByte(); // High byte
|
||||
result = (result<<8) | ReadByte(); // Low byte
|
||||
return (int16_t)result;
|
||||
}
|
||||
|
||||
int32_t DataFlash_APM2::ReadLong()
|
||||
{
|
||||
uint32_t result;
|
||||
|
||||
result = ReadByte(); // First byte
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte(); // Last byte
|
||||
return (int32_t)result;
|
||||
}
|
||||
|
||||
void DataFlash_APM2::SetFileNumber(uint16_t FileNumber)
|
||||
{
|
||||
df_FileNumber = FileNumber;
|
||||
df_FilePage = 1;
|
||||
}
|
||||
|
||||
uint16_t DataFlash_APM2::GetFileNumber()
|
||||
{
|
||||
return df_FileNumber;
|
||||
}
|
||||
|
||||
uint16_t DataFlash_APM2::GetFilePage()
|
||||
{
|
||||
return df_FilePage;
|
||||
}
|
||||
|
@ -9,19 +9,6 @@
|
||||
class DataFlash_APM2 : public DataFlash_Class
|
||||
{
|
||||
private:
|
||||
// DataFlash Log variables...
|
||||
unsigned char df_BufferNum;
|
||||
unsigned char df_Read_BufferNum;
|
||||
unsigned int df_BufferIdx;
|
||||
unsigned int df_Read_BufferIdx;
|
||||
unsigned int df_PageAdr;
|
||||
unsigned int df_Read_PageAdr;
|
||||
unsigned char df_Read_END;
|
||||
unsigned char df_Stop_Write;
|
||||
|
||||
uint16_t df_FileNumber;
|
||||
uint16_t df_FilePage;
|
||||
|
||||
//Methods
|
||||
unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr);
|
||||
void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data);
|
||||
@ -38,36 +25,12 @@ class DataFlash_APM2 : public DataFlash_Class
|
||||
|
||||
|
||||
public:
|
||||
unsigned char df_manufacturer;
|
||||
unsigned char df_device_0;
|
||||
unsigned char df_device_1;
|
||||
uint16_t df_PageSize;
|
||||
uint16_t df_NumPages;
|
||||
|
||||
DataFlash_APM2(); // Constructor
|
||||
void Init();
|
||||
void ReadManufacturerID();
|
||||
bool CardInserted();
|
||||
int16_t GetPage();
|
||||
int16_t GetWritePage();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
// Write methods
|
||||
void StartWrite(int16_t PageAdr);
|
||||
void FinishWrite();
|
||||
void WriteByte(unsigned char data);
|
||||
void WriteInt(int16_t data);
|
||||
void WriteLong(int32_t data);
|
||||
|
||||
// Read methods
|
||||
void StartRead(int16_t PageAdr);
|
||||
unsigned char ReadByte();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
|
||||
void SetFileNumber(uint16_t FileNumber);
|
||||
uint16_t GetFileNumber();
|
||||
uint16_t GetFilePage();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user