purple: rework DataFlash to separate purple and APM1 hardware support

the purple support is still a work in progress, but the APM1 support
should be fine
This commit is contained in:
Pat Hickey 2011-11-13 14:29:07 +11:00
parent c65a8c4616
commit afef359ee9
5 changed files with 1076 additions and 567 deletions

View File

@ -1,115 +1,42 @@
/* ************************************************************ */
/* Test for DataFlash Log library */
/* ************************************************************ */
#ifndef DataFlash_h
#define DataFlash_h
#include "../FastSerial/FastSerial.h"
// flash size
#define DF_LAST_PAGE 4096
// arduino mega SPI pins
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define DF_DATAOUT 51 // MOSI
#define DF_DATAIN 50 // MISO
#define DF_SPICLOCK 52 // SCK
#define DF_SLAVESELECT 53 // SS (PB0)
#define DF_RESET 31 // RESET (PC6)
#else // normal arduino SPI pins...
#define DF_DATAOUT 11 //MOSI
#define DF_DATAIN 12 //MISO
#define DF_SPICLOCK 13 //SCK
#define DF_SLAVESELECT 10 //SS
#endif
// AT45DB161D Commands (from Datasheet)
#define DF_TRANSFER_PAGE_TO_BUFFER_1 0x53
#define DF_TRANSFER_PAGE_TO_BUFFER_2 0x55
#define DF_STATUS_REGISTER_READ 0xD7
#define DF_READ_MANUFACTURER_AND_DEVICE_ID 0x9F
#define DF_PAGE_READ 0xD2
#define DF_BUFFER_1_READ 0xD4
#define DF_BUFFER_2_READ 0xD6
#define DF_BUFFER_1_WRITE 0x84
#define DF_BUFFER_2_WRITE 0x87
#define DF_BUFFER_1_TO_PAGE_WITH_ERASE 0x83
#define DF_BUFFER_2_TO_PAGE_WITH_ERASE 0x86
#define DF_PAGE_ERASE 0x81
#define DF_BLOCK_ERASE 0x50
#define DF_SECTOR_ERASE 0x7C
#define DF_CHIP_ERASE_0 0xC7
#define DF_CHIP_ERASE_1 0x94
#define DF_CHIP_ERASE_2 0x80
#define DF_CHIP_ERASE_3 0x9A
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_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);
void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr);
void WaitReady();
unsigned char ReadStatusReg();
unsigned char ReadStatus();
uint16_t PageSize();
public:
unsigned char df_manufacturer;
unsigned char df_device_0;
unsigned char df_device_1;
uint16_t df_PageSize;
DataFlash_Class(); // 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();
};
extern DataFlash_Class DataFlash;
/* ************************************************************ */
/* Test for DataFlash Log library */
/* ************************************************************ */
#ifndef DataFlash_h
#define DataFlash_h
#include <stdint.h>
class DataFlash_Class
{
public:
DataFlash_Class() {} // Constructor
virtual void Init() = 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;
// 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;
// Read methods
virtual void StartRead(int PageAdr) = 0;
virtual unsigned char ReadByte() = 0;
virtual int16_t ReadInt() = 0;
virtual int32_t ReadLong() = 0;
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFileNumber();
uint16_t GetFilePage();
};
#include "DataFlash_APM1.h"
#include "DataFlash_Purple.h"
#endif

View File

@ -1,454 +1,454 @@
/*
DataFlash.cpp - DataFlash log library for AT45DB161
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
This code works with boards based on ATMega168/328 and ATMega1280/2560 using SPI port
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
Dataflash library for AT45DB161D flash memory
Memory organization : 4096 pages of 512 bytes or 528 bytes
Maximun write bandwidth : 512 bytes in 14ms
This code is written so the master never has to wait to write the data on the eeprom
Methods:
Init() : Library initialization (SPI initialization)
StartWrite(page) : Start a write session. page=start page.
WriteByte(data) : Write a byte
WriteInt(data) : Write an integer (2 bytes)
WriteLong(data) : Write a long (4 bytes)
StartRead(page) : Start a read on (page)
GetWritePage() : Returns the last page written to
GetPage() : Returns the last page read
ReadByte()
ReadInt()
ReadLong()
Properties:
*/
/*
DataFlash_APM1.cpp - DataFlash log library for AT45DB161
Code by Jordi Munoz and Jose Julio. DIYDrones.com
This code works with boards based on ATMega168/328 and ATMega1280/2560 using SPI port
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
Dataflash library for AT45DB161D flash memory
Memory organization : 4096 pages of 512 bytes or 528 bytes
Maximun write bandwidth : 512 bytes in 14ms
This code is written so the master never has to wait to write the data on the eeprom
Methods:
Init() : Library initialization (SPI initialization)
StartWrite(page) : Start a write session. page=start page.
WriteByte(data) : Write a byte
WriteInt(data) : Write an integer (2 bytes)
WriteLong(data) : Write a long (4 bytes)
StartRead(page) : Start a read on (page)
GetWritePage() : Returns the last page written to
GetPage() : Returns the last page read
ReadByte()
ReadInt()
ReadLong()
Properties:
*/
#include <stdint.h>
#include "DataFlash.h"
#include <SPI.h>
#define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwriting from page 1
// *** INTERNAL FUNCTIONS ***
void dataflash_CS_inactive()
{
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
}
void dataflash_CS_active()
{
digitalWrite(DF_SLAVESELECT,LOW); //enable device
}
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_Class::DataFlash_Class()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_Class::Init(void)
{
pinMode(DF_DATAOUT, OUTPUT);
pinMode(DF_DATAIN, INPUT);
pinMode(DF_SPICLOCK,OUTPUT);
pinMode(DF_SLAVESELECT,OUTPUT);
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
pinMode(DF_RESET,OUTPUT);
// Reset the chip
digitalWrite(DF_RESET,LOW);
delay(1);
digitalWrite(DF_RESET,HIGH);
#endif
df_Read_END=false;
dataflash_CS_inactive(); //disable device
// Setup SPI Master, Mode 3, fosc/4 = 4MHz
SPI.begin();
SPI.setBitOrder(MSBFIRST);
SPI.setDataMode(SPI_MODE3);
SPI.setClockDivider(SPI_CLOCK_DIV2);
// get page size: 512 or 528
df_PageSize=PageSize();
}
// This function is mainly to test the device
void DataFlash_Class::ReadManufacturerID()
{
dataflash_CS_active(); // activate dataflash command decoder
// Read manufacturer and ID command...
SPI.transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
df_manufacturer = SPI.transfer(0xff);
df_device_0 = SPI.transfer(0xff);
df_device_1 = SPI.transfer(0xff);
SPI.transfer(0xff);
dataflash_CS_inactive(); // Reset dataflash command decoder
}
// Read the status register
byte DataFlash_Class::ReadStatusReg()
{
byte tmp;
dataflash_CS_active(); // activate dataflash command decoder
// Read status command
SPI.transfer(DF_STATUS_REGISTER_READ);
tmp = SPI.transfer(0x00); // We only want to extract the READY/BUSY bit
dataflash_CS_inactive(); // Reset dataflash command decoder
return tmp;
}
// Read the status of the DataFlash
inline
byte DataFlash_Class::ReadStatus()
{
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
}
inline
unsigned int DataFlash_Class::PageSize()
{
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
}
// Wait until DataFlash is in ready state...
void DataFlash_Class::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_Class::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
else
SPI.transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
SPI.transfer(0x00); // don´t care bytes
dataflash_CS_inactive(); //initiate the transfer
dataflash_CS_active();
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive();
}
void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
else
SPI.transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
SPI.transfer(0x00); // don´t care bytes
dataflash_CS_inactive(); //initiate the transfer
dataflash_CS_active();
// Check if we need to wait to write the buffer to memory or we can continue...
if (wait)
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive(); //deactivate dataflash command decoder
}
void DataFlash_Class::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_WRITE);
else
SPI.transfer(DF_BUFFER_2_WRITE);
SPI.transfer(0x00); //don't cares
SPI.transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI.transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI.transfer(Data); //write data byte
dataflash_CS_inactive(); // disable dataflash command decoder
}
unsigned char DataFlash_Class::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
{
byte tmp;
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_READ);
else
SPI.transfer(DF_BUFFER_2_READ);
SPI.transfer(0x00); //don't cares
SPI.transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI.transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI.transfer(0x00); //don't cares
tmp = SPI.transfer(0x00); //read data byte
dataflash_CS_inactive(); // deactivate dataflash command decoder
return (tmp);
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_Class::PageErase (unsigned int PageAdr)
{
dataflash_CS_active(); // activate dataflash command decoder
SPI.transfer(DF_PAGE_ERASE); // Command
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
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_Class::ChipErase ()
{
dataflash_CS_active(); // activate dataflash command decoder
// opcodes for chip erase
SPI.transfer(DF_CHIP_ERASE_0);
SPI.transfer(DF_CHIP_ERASE_1);
SPI.transfer(DF_CHIP_ERASE_2);
SPI.transfer(DF_CHIP_ERASE_3);
dataflash_CS_inactive(); //initiate flash page erase
dataflash_CS_active();
while(!ReadStatus());
dataflash_CS_inactive(); // deactivate dataflash command decoder
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Class::StartWrite(int 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_Class::FinishWrite(void)
{
df_BufferIdx=0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
df_PageAdr++;
if (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_Class::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 (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_Class::WriteInt(int data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
}
void DataFlash_Class::WriteLong(long data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
WriteByte(data>>8);
WriteByte(data&0xFF); // Last byte
}
// Get the last page written to
int DataFlash_Class::GetWritePage()
{
return(df_PageAdr);
}
// Get the last page read
int DataFlash_Class::GetPage()
{
return(df_Read_PageAdr-1);
}
void DataFlash_Class::StartRead(int 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_Class::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;
}
int DataFlash_Class::ReadInt()
{
int result;
result = ReadByte(); // High byte
result = (result<<8) | ReadByte(); // Low byte
return result;
}
long DataFlash_Class::ReadLong()
{
long result;
result = ReadByte(); // First byte
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte(); // Last byte
return result;
}
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
{
return df_FilePage;
}
// make one instance for the user to use
DataFlash_Class DataFlash;
#include "DataFlash.h"
#include <SPI.h>
#define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwriting from page 1
// *** INTERNAL FUNCTIONS ***
void dataflash_CS_inactive()
{
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
}
void dataflash_CS_active()
{
digitalWrite(DF_SLAVESELECT,LOW); //enable device
}
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_APM1::DataFlash_APM1()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_APM1::Init(void)
{
pinMode(DF_DATAOUT, OUTPUT);
pinMode(DF_DATAIN, INPUT);
pinMode(DF_SPICLOCK,OUTPUT);
pinMode(DF_SLAVESELECT,OUTPUT);
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
pinMode(DF_RESET,OUTPUT);
// Reset the chip
digitalWrite(DF_RESET,LOW);
delay(1);
digitalWrite(DF_RESET,HIGH);
#endif
df_Read_END=false;
dataflash_CS_inactive(); //disable device
// Setup SPI Master, Mode 3, fosc/4 = 4MHz
SPI.begin();
SPI.setBitOrder(MSBFIRST);
SPI.setDataMode(SPI_MODE3);
SPI.setClockDivider(SPI_CLOCK_DIV2);
// get page size: 512 or 528
df_PageSize=PageSize();
}
// This function is mainly to test the device
void DataFlash_APM1::ReadManufacturerID()
{
dataflash_CS_active(); // activate dataflash command decoder
// Read manufacturer and ID command...
SPI.transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
df_manufacturer = SPI.transfer(0xff);
df_device_0 = SPI.transfer(0xff);
df_device_1 = SPI.transfer(0xff);
SPI.transfer(0xff);
dataflash_CS_inactive(); // Reset dataflash command decoder
}
// Read the status register
byte DataFlash_APM1::ReadStatusReg()
{
byte tmp;
dataflash_CS_active(); // activate dataflash command decoder
// Read status command
SPI.transfer(DF_STATUS_REGISTER_READ);
tmp = SPI.transfer(0x00); // We only want to extract the READY/BUSY bit
dataflash_CS_inactive(); // Reset dataflash command decoder
return tmp;
}
// Read the status of the DataFlash
inline
byte DataFlash_APM1::ReadStatus()
{
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
}
inline
unsigned int DataFlash_APM1::PageSize()
{
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
}
// Wait until DataFlash is in ready state...
void DataFlash_APM1::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
else
SPI.transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
SPI.transfer(0x00); // don´t care bytes
dataflash_CS_inactive(); //initiate the transfer
dataflash_CS_active();
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive();
}
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
else
SPI.transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
SPI.transfer(0x00); // don´t care bytes
dataflash_CS_inactive(); //initiate the transfer
dataflash_CS_active();
// Check if we need to wait to write the buffer to memory or we can continue...
if (wait)
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
dataflash_CS_inactive(); //deactivate dataflash command decoder
}
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
{
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_WRITE);
else
SPI.transfer(DF_BUFFER_2_WRITE);
SPI.transfer(0x00); //don't cares
SPI.transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI.transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI.transfer(Data); //write data byte
dataflash_CS_inactive(); // disable dataflash command decoder
}
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
{
byte tmp;
dataflash_CS_active(); // activate dataflash command decoder
if (BufferNum==1)
SPI.transfer(DF_BUFFER_1_READ);
else
SPI.transfer(DF_BUFFER_2_READ);
SPI.transfer(0x00); //don't cares
SPI.transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI.transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI.transfer(0x00); //don't cares
tmp = SPI.transfer(0x00); //read data byte
dataflash_CS_inactive(); // deactivate dataflash command decoder
return (tmp);
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_APM1::PageErase (unsigned int PageAdr)
{
dataflash_CS_active(); // activate dataflash command decoder
SPI.transfer(DF_PAGE_ERASE); // Command
if(df_PageSize==512){
SPI.transfer((unsigned char)(PageAdr >> 7));
SPI.transfer((unsigned char)(PageAdr << 1));
}else{
SPI.transfer((unsigned char)(PageAdr >> 6));
SPI.transfer((unsigned char)(PageAdr << 2));
}
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 ()
{
dataflash_CS_active(); // activate dataflash command decoder
// opcodes for chip erase
SPI.transfer(DF_CHIP_ERASE_0);
SPI.transfer(DF_CHIP_ERASE_1);
SPI.transfer(DF_CHIP_ERASE_2);
SPI.transfer(DF_CHIP_ERASE_3);
dataflash_CS_inactive(); //initiate flash page erase
dataflash_CS_active();
while(!ReadStatus());
dataflash_CS_inactive(); // deactivate dataflash command decoder
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_APM1::StartWrite(int 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 (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 (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(int data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
}
void DataFlash_APM1::WriteLong(long data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
WriteByte(data>>8);
WriteByte(data&0xFF); // Last byte
}
// Get the last page written to
int DataFlash_APM1::GetWritePage()
{
return(df_PageAdr);
}
// Get the last page read
int DataFlash_APM1::GetPage()
{
return(df_Read_PageAdr-1);
}
void DataFlash_APM1::StartRead(int 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;
}
int DataFlash_APM1::ReadInt()
{
int result;
result = ReadByte(); // High byte
result = (result<<8) | ReadByte(); // Low byte
return result;
}
long DataFlash_APM1::ReadLong()
{
long result;
result = ReadByte(); // First byte
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte(); // Last byte
return 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;
}
// make one instance for the user to use
DataFlash_APM1 DataFlash;

View File

@ -0,0 +1,64 @@
/* ************************************************************ */
/* Test for DataFlash Log library */
/* ************************************************************ */
#ifndef __DATAFLASH_APM1_H__
#define __DATAFLASH_APM1_H__
#include "DataFlash.h"
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);
void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr);
void WaitReady();
unsigned char ReadStatusReg();
unsigned char ReadStatus();
uint16_t PageSize();
public:
unsigned char df_manufacturer;
unsigned char df_device_0;
unsigned char df_device_1;
unsigned int df_PageSize;
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(int 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__

View File

@ -0,0 +1,454 @@
/*
DataFlash_Purple.cpp - DataFlash log library for AT45DB321D
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
This code works only on ATMega2560. It uses Serial port 3 in SPI MSPI mdoe.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
Dataflash library for AT45DB321D flash memory
Memory organization : 8192 pages of 512 bytes or 528 bytes
Maximun write bandwidth : 512 bytes in 14ms
This code is written so the master never has to wait to write the data on the eeprom
Methods:
Init() : Library initialization (SPI initialization)
StartWrite(page) : Start a write session. page=start page.
WriteByte(data) : Write a byte
WriteInt(data) : Write an integer (2 bytes)
WriteLong(data) : Write a long (4 bytes)
StartRead(page) : Start a read on (page)
GetWritePage() : Returns the last page written to
GetPage() : Returns the last page read
ReadByte()
ReadInt()
ReadLong()
Properties:
*/
extern "C" {
// AVR LibC Includes
#include <inttypes.h>
#include <avr/interrupt.h>
#include "WConstants.h"
}
#include "DataFlash_Purple.h"
// DataFlash is connected to Serial Port 3 (we will use SPI mode)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define DF_DATAOUT 14 // MOSI
#define DF_DATAIN 15 // MISO
#define DF_SPICLOCK PJ2 // SCK
#define DF_SLAVESELECT 28 // SS (PA6)
#define DF_RESET 41 // RESET (PG0)
#define DF_CARDDETECT 33 // PC4
#else
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.
#endif
#define DF_MAX_PAGE 8192
// AT45DB321D Commands (from Datasheet)
#define DF_TRANSFER_PAGE_TO_BUFFER_1 0x53
#define DF_TRANSFER_PAGE_TO_BUFFER_2 0x55
#define DF_STATUS_REGISTER_READ 0xD7
#define DF_READ_MANUFACTURER_AND_DEVICE_ID 0x9F
#define DF_PAGE_READ 0xD2
#define DF_BUFFER_1_READ 0xD4
#define DF_BUFFER_2_READ 0xD6
#define DF_BUFFER_1_WRITE 0x84
#define DF_BUFFER_2_WRITE 0x87
#define DF_BUFFER_1_TO_PAGE_WITH_ERASE 0x83
#define DF_BUFFER_2_TO_PAGE_WITH_ERASE 0x86
#define DF_PAGE_ERASE 0x81
#define DF_BLOCK_ERASE 0x50
#define DF_SECTOR_ERASE 0x7C
#define DF_CHIP_ERASE_0 0xC7
#define DF_CHIP_ERASE_1 0x94
#define DF_CHIP_ERASE_2 0x80
#define DF_CHIP_ERASE_3 0x9A
#define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1
// *** INTERNAL FUNCTIONS ***
unsigned char DataFlash_Purple::SPI_transfer(unsigned char data)
{
/* Wait for empty transmit buffer */
while ( !( UCSR3A & (1<<UDRE3)) );
/* Put data into buffer, sends the data */
UDR3 = data;
/* Wait for data to be received */
while ( !(UCSR3A & (1<<RXC3)) );
/* Get and return received data from buffer */
return UDR3;
}
void DataFlash_Purple::CS_inactive()
{
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
}
void DataFlash_Purple::CS_active()
{
digitalWrite(DF_SLAVESELECT,LOW); //enable device
}
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_Purple::DataFlash_Purple()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_Purple::Init(void)
{
pinMode(DF_DATAOUT, OUTPUT);
pinMode(DF_DATAIN, INPUT);
pinMode(DF_SLAVESELECT,OUTPUT);
pinMode(DF_RESET,OUTPUT);
pinMode(DF_CARDDETECT, INPUT);
// Reset the chip
digitalWrite(DF_RESET,LOW);
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
UBRR3 = 0;
DDRJ |= (1<<PJ2); // SPI clock XCK3 (PJ2) as output. This enable SPI Master mode
// Set MSPI mode of operation and SPI data mode 0.
UCSR3C = (1<<UMSEL31)|(1<<UMSEL30); //|(1<<1)|(1<<UCPOL3);
// Enable receiver and transmitter.
UCSR3B = (1<<RXEN3)|(1<<TXEN3);
// Set Baud rate
UBRR3 = 0; // SPI running at 8Mhz
// get page size: 512 or 528 (by default: 528)
df_PageSize=PageSize();
}
// This function is mainly to test the device
void DataFlash_Purple::ReadManufacturerID()
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
// Read manufacturer and ID command...
SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
df_manufacturer = SPI_transfer(0xff);
df_device_0 = SPI_transfer(0xff);
df_device_1 = SPI_transfer(0xff);
SPI_transfer(0xff);
}
// This function return 1 if Card is inserted on SD slot
int DataFlash_Purple::CardInserted()
{
return (!digitalRead(DF_CARDDETECT));
}
// Read the status register
byte DataFlash_Purple::ReadStatusReg()
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
// Read status command
SPI_transfer(DF_STATUS_REGISTER_READ);
return SPI_transfer(0x00); // We only want to extract the READY/BUSY bit
}
// Read the status of the DataFlash
inline
byte DataFlash_Purple::ReadStatus()
{
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
}
inline
unsigned int DataFlash_Purple::PageSize()
{
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
}
// Wait until DataFlash is in ready state...
void DataFlash_Purple::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
{
CS_inactive();
CS_active();
if (BufferNum==1)
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
else
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
if(df_PageSize==512){
SPI_transfer((unsigned char)(PageAdr >> 7));
SPI_transfer((unsigned char)(PageAdr << 1));
}else{
SPI_transfer((unsigned char)(PageAdr >> 6));
SPI_transfer((unsigned char)(PageAdr << 2));
}
SPI_transfer(0x00); // don´t care bytes
CS_inactive(); //initiate the transfer
CS_active();
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
}
void DataFlash_Purple::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
if (BufferNum==1)
SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
else
SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
if(df_PageSize==512){
SPI_transfer((unsigned char)(PageAdr >> 7));
SPI_transfer((unsigned char)(PageAdr << 1));
}else{
SPI_transfer((unsigned char)(PageAdr >> 6));
SPI_transfer((unsigned char)(PageAdr << 2));
}
SPI_transfer(0x00); // don´t care bytes
CS_inactive(); //initiate the transfer
CS_active();
// Check if we need to wait to write the buffer to memory or we can continue...
if (wait)
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
}
void DataFlash_Purple::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
{
CS_inactive(); // Reset dataflash command decoder
CS_active();
if (BufferNum==1)
SPI_transfer(DF_BUFFER_1_WRITE);
else
SPI_transfer(DF_BUFFER_2_WRITE);
SPI_transfer(0x00); //don't cares
SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI_transfer(Data); //write data byte
}
unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
{
byte tmp;
CS_inactive(); // Reset dataflash command decoder
CS_active();
if (BufferNum==1)
SPI_transfer(DF_BUFFER_1_READ);
else
SPI_transfer(DF_BUFFER_2_READ);
SPI_transfer(0x00); //don't cares
SPI_transfer((unsigned char)(IntPageAdr>>8)); //upper part of internal buffer address
SPI_transfer((unsigned char)(IntPageAdr)); //lower part of internal buffer address
SPI_transfer(0x00); //don't cares
tmp = SPI_transfer(0x00); //read data byte
return (tmp);
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_Purple::PageErase (unsigned int PageAdr)
{
CS_inactive(); //make sure to toggle CS signal in order
CS_active(); //to reset Dataflash command decoder
SPI_transfer(DF_PAGE_ERASE); // Command
if(df_PageSize==512){
SPI_transfer((unsigned char)(PageAdr >> 7));
SPI_transfer((unsigned char)(PageAdr << 1));
}else{
SPI_transfer((unsigned char)(PageAdr >> 6));
SPI_transfer((unsigned char)(PageAdr << 2));
}
SPI_transfer(0x00); // "dont cares"
CS_inactive(); //initiate flash page erase
CS_active();
while(!ReadStatus());
}
void DataFlash_Purple::ChipErase ()
{
CS_inactive(); //make sure to toggle CS signal in order
CS_active(); //to reset Dataflash command decoder
// opcodes for chip erase
SPI_transfer(DF_CHIP_ERASE_0);
SPI_transfer(DF_CHIP_ERASE_1);
SPI_transfer(DF_CHIP_ERASE_2);
SPI_transfer(DF_CHIP_ERASE_3);
CS_inactive(); //initiate flash page erase
CS_active();
while(!ReadStatus());
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Purple::StartWrite(int PageAdr)
{
df_BufferNum=1;
df_BufferIdx=0;
df_PageAdr=PageAdr;
df_Stop_Write=0;
WaitReady();
}
void DataFlash_Purple::FinishWrite(void)
{
df_BufferIdx=0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
df_PageAdr++;
if (OVERWRITE_DATA==1)
{
if (df_PageAdr>=DF_MAX_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
}
else
{
if (df_PageAdr>=DF_MAX_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_Purple::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=0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
df_PageAdr++;
if (OVERWRITE_DATA==1)
{
if (df_PageAdr>=DF_MAX_PAGE) // If we reach the end of the memory, start from the begining
df_PageAdr = 1;
}
else
{
if (df_PageAdr>=DF_MAX_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_Purple::WriteInt(int data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
}
void DataFlash_Purple::WriteLong(long data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
WriteByte(data>>8);
WriteByte(data&0xFF); // Last byte
}
// Get the last page written to
int DataFlash_Purple::GetWritePage()
{
return(df_PageAdr);
}
// Get the last page read
int DataFlash_Purple::GetPage()
{
return(df_Read_PageAdr-1);
}
void DataFlash_Purple::StartRead(int PageAdr)
{
df_Read_BufferNum=1;
df_Read_BufferIdx=0;
df_Read_PageAdr=PageAdr;
WaitReady();
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write Memory page to buffer
df_Read_PageAdr++;
}
byte DataFlash_Purple::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=0;
PageToBuffer(df_Read_BufferNum,df_Read_PageAdr); // Write memory page to Buffer
df_Read_PageAdr++;
if (df_Read_PageAdr>=DF_MAX_PAGE) // If we reach the end of the memory, start from the begining
{
df_Read_PageAdr = 0;
df_Read_END = true;
}
}
return result;
}
int DataFlash_Purple::ReadInt()
{
int result;
result = ReadByte(); // High byte
result = (result<<8) | ReadByte(); // Low byte
return result;
}
long DataFlash_Purple::ReadLong()
{
long result;
result = ReadByte(); // First byte
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte();
result = (result<<8) | ReadByte(); // Last byte
return result;
}

View File

@ -0,0 +1,64 @@
/* ************************************************************ */
/* DataFlash_Purple Log library */
/* ************************************************************ */
#ifndef __DATAFLASH_PURPLE_H__
#define __DATAFLASH_PURPLE_H__
#include "DataFlash.h"
class DataFlash_Purple : 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;
//Methods
unsigned char BufferRead (unsigned char BufferNum, unsigned int IntPageAdr);
void BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data);
void BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, unsigned int PageAdr);
void WaitReady();
unsigned char ReadStatusReg();
unsigned char ReadStatus();
unsigned int PageSize();
unsigned char SPI_transfer(unsigned char data);
void CS_inactive();
void CS_active();
public:
unsigned char df_manufacturer;
unsigned char df_device_0;
unsigned char df_device_1;
unsigned int df_PageSize;
DataFlash_Purple(); // Constructor
void Init();
void ReadManufacturerID();
int CardInserted();
int GetPage();
int GetWritePage();
void PageErase (unsigned int PageAdr);
void ChipErase ();
// Write methods
void StartWrite(int PageAdr);
void FinishWrite();
void WriteByte(unsigned char data);
void WriteInt(int data);
void WriteLong(long data);
// Read methods
void StartRead(int PageAdr);
unsigned char ReadByte();
int ReadInt();
long ReadLong();
};
#endif