/* 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 #include #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<> 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, uint16_t 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, uint16_t 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, uint16_t 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 (uint16_t 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(int16_t 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(int16_t data) { WriteByte(data>>8); // High byte WriteByte(data&0xFF); // Low byte } void DataFlash_Purple::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_Purple::GetWritePage() { return(df_PageAdr); } // Get the last page read int16_t DataFlash_Purple::GetPage() { return(df_Read_PageAdr-1); } void DataFlash_Purple::StartRead(int16_t 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; } int16_t DataFlash_Purple::ReadInt() { uint16_t result; result = ReadByte(); // High byte result = (result<<8) | ReadByte(); // Low byte return (int16_t)result; } int32_t DataFlash_Purple::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; }