DataFlash: added block based dataflash writes

these are about 10x faster than the old writes
This commit is contained in:
Andrew Tridgell 2013-01-12 17:21:04 +11:00
parent 252d11ccfa
commit 28a0ba6c4a
7 changed files with 243 additions and 155 deletions

View File

@ -12,87 +12,72 @@ extern AP_HAL::HAL& hal;
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Class::StartWrite(int16_t PageAdr)
{
df_BufferNum=1;
df_BufferIdx=4;
df_PageAdr=PageAdr;
df_Stop_Write=0;
df_BufferIdx = 0;
df_BufferNum = 0;
df_PageAdr = PageAdr;
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_Class::FinishWrite(void)
{
df_BufferIdx=0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
// Write Buffer to flash, NO WAIT
BufferToPage(df_BufferNum, df_PageAdr, 0);
df_PageAdr++;
if (DF_OVERWRITE_DATA==1) {
if (df_PageAdr>df_NumPages) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
} else {
if (df_PageAdr>df_NumPages) // If we reach the end of the memory, stop here
df_Stop_Write=1;
}
// If we reach the end of the memory, start from the begining
if (df_PageAdr > df_NumPages)
df_PageAdr = 1;
if (df_BufferNum==1) // Change buffer to continue writing...
df_BufferNum=2;
else
df_BufferNum=1;
// switch buffer
df_BufferNum ^= 1;
df_BufferIdx = 0;
}
void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size)
{
while (size > 0) {
uint16_t n = df_PageSize - df_BufferIdx;
if (n > size) {
n = size;
}
if (df_BufferIdx == 0) {
// if we are at the start of a page we need to insert a
// page header
if (n > df_PageSize - sizeof(struct PageHeader)) {
n -= sizeof(struct PageHeader);
}
struct PageHeader ph = { df_FileNumber, df_FilePage };
BlockWrite(df_BufferNum, df_BufferIdx, &ph, sizeof(ph), pBuffer, n);
df_BufferIdx += n + sizeof(ph);
} else {
BlockWrite(df_BufferNum, df_BufferIdx, NULL, 0, pBuffer, n);
df_BufferIdx += n;
}
size -= n;
pBuffer = (const void *)(n + (uintptr_t)pBuffer);
if (df_BufferIdx == df_PageSize) {
FinishWrite();
df_FilePage++;
}
}
}
void DataFlash_Class::WriteByte(uint8_t 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_NumPages) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
}
else
{
if (df_PageAdr>df_NumPages) // 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
}
}
WriteBlock(&data, sizeof(data));
}
void DataFlash_Class::WriteInt(int16_t data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
WriteBlock(&data, sizeof(data));
}
void DataFlash_Class::WriteLong(int32_t data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
WriteByte(data>>8);
WriteByte(data&0xFF); // Last byte
WriteBlock(&data, sizeof(data));
}
// Get the last page written to
@ -109,67 +94,75 @@ int16_t DataFlash_Class::GetPage()
void DataFlash_Class::StartRead(int16_t PageAdr)
{
df_Read_BufferNum=1;
df_Read_BufferIdx=4;
df_Read_PageAdr=PageAdr;
df_Read_BufferNum = 0;
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++;
// copy flash page to buffer
PageToBuffer(df_Read_BufferNum, 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
struct PageHeader ph;
BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph));
df_FileNumber = ph.FileNumber;
df_FilePage = ph.FilePage;
df_Read_BufferIdx = sizeof(ph);
}
void DataFlash_Class::ReadBlock(void *pBuffer, uint16_t size)
{
while (size > 0) {
uint16_t n = df_PageSize - df_Read_BufferIdx;
if (n > size) {
n = size;
}
WaitReady();
BlockRead(df_Read_BufferNum, df_Read_BufferIdx, pBuffer, n);
size -= n;
pBuffer = (void *)(n + (uintptr_t)pBuffer);
df_Read_BufferIdx += n;
if (df_Read_BufferIdx == df_PageSize) {
df_Read_PageAdr++;
if (df_Read_PageAdr > df_NumPages) {
df_Read_PageAdr = 1;
}
PageToBuffer(df_Read_BufferNum, df_Read_PageAdr);
// We are starting a new page - read FileNumber and FilePage
struct PageHeader ph;
BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph));
df_FileNumber = ph.FileNumber;
df_FilePage = ph.FilePage;
df_Read_BufferIdx = sizeof(ph);
}
}
}
uint8_t DataFlash_Class::ReadByte()
{
uint8_t 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_NumPages) // If we reach the end of the memory, start from the begining
{
df_Read_PageAdr = 0;
}
// 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
}
uint8_t result = 0;
ReadBlock(&result, sizeof(result));
return result;
}
int16_t DataFlash_Class::ReadInt()
{
uint16_t result;
result = ReadByte(); // High byte
result = (result<<8) | ReadByte(); // Low byte
return (int16_t)result;
int16_t result;
ReadBlock(&result, sizeof(result));
return result;
}
int32_t DataFlash_Class::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;
int32_t result;
ReadBlock(&result, sizeof(result));
return result;
}
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
@ -221,11 +214,15 @@ uint8_t DataFlash_Class::get_num_logs(void)
uint16_t last;
uint16_t first;
if(find_last_page() == 1) return 0;
if (find_last_page() == 1) {
return 0;
}
StartRead(1);
if(GetFileNumber() == 0XFFFF) return 0;
if (GetFileNumber() == 0XFFFF) {
return 0;
}
lastpage = find_last_page();
StartRead(lastpage);

View File

@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/* ************************************************************ */
/* Test for DataFlash Log library */
/* ************************************************************ */
@ -6,11 +8,9 @@
#include <stdint.h>
#define DF_OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwriting from page 1
// the last page holds the log format in first 4 bytes. Please change
// this if (and only if!) the low level format changes
#define DF_LOGGING_FORMAT 0x28122011
#define DF_LOGGING_FORMAT 0x28122013
// we use an invalie logging format to test the chip erase
#define DF_LOGGING_FORMAT_INVALID 0x28122012
@ -18,6 +18,11 @@
class DataFlash_Class
{
private:
struct PageHeader {
uint16_t FileNumber;
uint16_t FilePage;
};
// DataFlash Log variables...
uint8_t df_BufferNum;
uint8_t df_Read_BufferNum;
@ -25,19 +30,28 @@ private:
uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr;
uint16_t df_Read_PageAdr;
uint8_t df_Stop_Write;
uint16_t df_FileNumber;
uint16_t df_FilePage;
virtual void WaitReady() = 0;
virtual void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data) = 0;
virtual void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait) = 0;
virtual void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr) = 0;
virtual uint8_t BufferRead (uint8_t BufferNum, uint16_t IntPageAdr) = 0;
virtual void PageErase(uint16_t PageAdr) = 0;
virtual void BlockErase(uint16_t BlockAdr) = 0;
virtual void ChipErase() = 0;
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size) = 0;
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) = 0;
// internal high level functions
int16_t find_last_page(void);
int16_t find_last_page_of_log(uint16_t log_number);
@ -65,12 +79,15 @@ public:
// Write methods
void StartWrite(int16_t PageAdr);
void FinishWrite(void);
void WriteBlock(const void *pBuffer, uint16_t size);
void WriteByte(uint8_t data);
void WriteInt(int16_t data);
void WriteLong(int32_t data);
// Read methods
void StartRead(int16_t PageAdr);
void ReadBlock(void *pBuffer, uint16_t size);
uint8_t ReadByte();
int16_t ReadInt();
int32_t ReadLong();

View File

@ -187,7 +187,7 @@ void DataFlash_APM1::PageToBuffer(uint8_t BufferNum, uint16_t PageAdr)
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
else
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
@ -216,7 +216,7 @@ void DataFlash_APM1::BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
else
_spi->transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
@ -240,7 +240,9 @@ void DataFlash_APM1::BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t
}
void DataFlash_APM1::BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data)
void DataFlash_APM1::BlockWrite (uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size)
{
if (!_spi_sem->take(1))
return;
@ -248,7 +250,7 @@ void DataFlash_APM1::BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_WRITE);
else
_spi->transfer(DF_BUFFER_2_WRITE);
@ -256,24 +258,35 @@ void DataFlash_APM1::BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_
_spi->transfer(0x00); // don't care
_spi->transfer((uint8_t)(IntPageAdr>>8)); // upper part of internal buffer address
_spi->transfer((uint8_t)(IntPageAdr)); // lower part of internal buffer address
_spi->transfer(Data); // write data byte
const uint8_t *pData;
// transfer header, if any
pData = (const uint8_t *)pHeader;
while (hdr_size--) {
_spi->transfer(*pData++);
}
// transfer data
pData = (const uint8_t *)pBuffer;
while (size--) {
_spi->transfer(*pData++);
}
// release SPI bus for use by other sensors
_spi->cs_release();
_spi_sem->give();
}
uint8_t DataFlash_APM1::BufferRead (uint8_t BufferNum, uint16_t IntPageAdr)
bool DataFlash_APM1::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
{
uint8_t tmp;
if (!_spi_sem->take(1))
return 0;
return false;
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_READ);
else
_spi->transfer(DF_BUFFER_2_READ);
@ -282,14 +295,19 @@ uint8_t DataFlash_APM1::BufferRead (uint8_t BufferNum, uint16_t IntPageAdr)
_spi->transfer((uint8_t)(IntPageAdr>>8)); // upper part of internal buffer address
_spi->transfer((uint8_t)(IntPageAdr)); // lower part of internal buffer address
_spi->transfer(0x00); // don't cares
tmp = _spi->transfer(0x00); // read data byte
uint8_t *pData = (uint8_t *)pBuffer;
while (size--) {
*pData++ = _spi->transfer(0x00);
}
// release SPI bus for use by other sensors
_spi->cs_release();
_spi_sem->give();
return (tmp);
return true;
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_APM1::PageErase (uint16_t PageAdr)

View File

@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/* ************************************************************ */
/* DataFlash_APM1 Log library */
/* ************************************************************ */
@ -11,17 +13,29 @@ class DataFlash_APM1 : public DataFlash_Class
{
private:
//Methods
uint8_t BufferRead (uint8_t BufferNum, uint16_t IntPageAdr);
void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
void WaitReady();
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
void WaitReady();
uint8_t ReadStatusReg();
uint8_t ReadStatus();
uint16_t PageSize();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase();
uint16_t PageSize();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase();
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
// If pHeader is not NULL then write the header bytes before the data
void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size);
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr,
void *pBuffer, uint16_t size);
AP_HAL::SPIDeviceDriver *_spi;
AP_HAL::Semaphore *_spi_sem;

View File

@ -194,7 +194,7 @@ void DataFlash_APM2::PageToBuffer(uint8_t BufferNum, uint16_t PageAdr)
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
else
_spi->transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
@ -226,7 +226,7 @@ void DataFlash_APM2::BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
else
_spi->transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
@ -251,14 +251,16 @@ void DataFlash_APM2::BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t
_spi_sem->give();
}
void DataFlash_APM2::BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data)
void DataFlash_APM2::BlockWrite (uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size)
{
if (!_spi_sem->take(1))
return;
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_WRITE);
else
_spi->transfer(DF_BUFFER_2_WRITE);
@ -266,24 +268,35 @@ void DataFlash_APM2::BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_
_spi->transfer(0x00); // don't care
_spi->transfer((uint8_t)(IntPageAdr>>8)); // upper part of internal buffer address
_spi->transfer((uint8_t)(IntPageAdr)); // lower part of internal buffer address
_spi->transfer(Data); // write data byte
const uint8_t *pData;
// transfer header, if any
pData = (const uint8_t *)pHeader;
while (hdr_size--) {
_spi->transfer(*pData++);
}
// transfer data
pData = (const uint8_t *)pBuffer;
while (size--) {
_spi->transfer(*pData++);
}
// release SPI bus for use by other sensors
_spi->cs_release();
_spi_sem->give();
}
uint8_t DataFlash_APM2::BufferRead (uint8_t BufferNum, uint16_t IntPageAdr)
bool DataFlash_APM2::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
{
if (!_spi_sem->take(1))
return 0;
uint8_t tmp;
return false;
// activate dataflash command decoder
_spi->cs_assert();
if (BufferNum==1)
if (BufferNum==0)
_spi->transfer(DF_BUFFER_1_READ);
else
_spi->transfer(DF_BUFFER_2_READ);
@ -292,14 +305,29 @@ uint8_t DataFlash_APM2::BufferRead (uint8_t BufferNum, uint16_t IntPageAdr)
_spi->transfer((uint8_t)(IntPageAdr>>8)); //upper part of internal buffer address
_spi->transfer((uint8_t)(IntPageAdr)); //lower part of internal buffer address
_spi->transfer(0x00); //don't cares
tmp = _spi->transfer(0x00); //read data byte
uint8_t *pData = (uint8_t *)pBuffer;
while (size--) {
*pData++ = _spi->transfer(0x00);
}
// release SPI bus for use by other sensors
_spi->cs_release();
_spi_sem->give();
return (tmp);
return true;
}
uint8_t DataFlash_APM2::BufferRead (uint8_t BufferNum, uint16_t IntPageAdr)
{
uint8_t tmp;
if (!BlockRead(BufferNum, IntPageAdr, &tmp, 1)) {
return 0;
}
return tmp;
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_APM2::PageErase (uint16_t PageAdr)

View File

@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/* ************************************************************ */
/* DataFlash_APM2 Log library */
/* ************************************************************ */
@ -11,15 +13,27 @@ class DataFlash_APM2 : public DataFlash_Class
{
private:
//Methods
uint8_t BufferRead (uint8_t BufferNum, uint16_t IntPageAdr);
void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
void WaitReady();
uint8_t ReadStatusReg();
uint8_t ReadStatus();
uint8_t ReadStatusReg();
uint8_t ReadStatus();
uint16_t PageSize();
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
// If pHeader is not NULL then write the header bytes before the data
void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size);
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
uint8_t BufferRead (uint8_t BufferNum, uint16_t IntPageAdr);
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase();

View File

@ -84,22 +84,22 @@ void DataFlash_SITL::WaitReady()
void DataFlash_SITL::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
{
pread(flash_fd, buffer[BufferNum-1], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
pread(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
}
void DataFlash_SITL::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
{
pwrite(flash_fd, buffer[BufferNum-1], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
pwrite(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
}
void DataFlash_SITL::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
{
buffer[BufferNum-1][IntPageAdr] = (uint8_t)Data;
buffer[BufferNum][IntPageAdr] = (uint8_t)Data;
}
unsigned char DataFlash_SITL::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
{
return (unsigned char)buffer[BufferNum-1][IntPageAdr];
return (unsigned char)buffer[BufferNum][IntPageAdr];
}
// *** END OF INTERNAL FUNCTIONS ***