• Main Page
  • Related Pages
  • Namespaces
  • Classes
  • Files
  • File List
  • File Members

DataFlash.cpp

Go to the documentation of this file.
00001 /*
00002         DataFlash.cpp - DataFlash log library for AT45DB161
00003         Code by Jordi Muñoz and Jose Julio. DIYDrones.com
00004         This code works with boards based on ATMega168/328 and ATMega1280/2560 using SPI port
00005 
00006         This library is free software; you can redistribute it and/or
00007     modify it under the terms of the GNU Lesser General Public
00008     License as published by the Free Software Foundation; either
00009     version 2.1 of the License, or (at your option) any later version.
00010 
00011         Dataflash library for AT45DB161D flash memory
00012         Memory organization : 4096 pages of 512 bytes
00013 
00014         Maximun write bandwidth : 512 bytes in 14ms
00015         This code is written so the master never has to wait to write the data on the eeprom
00016 
00017         Methods:
00018                 Init() : Library initialization (SPI initialization)
00019                 StartWrite(page) : Start a write session. page=start page.
00020                 WriteByte(data) : Write a byte
00021                 WriteInt(data) :  Write an integer (2 bytes)
00022                 WriteLong(data) : Write a long (4 bytes)
00023                 StartRead(page) : Start a read on (page)
00024                 GetWritePage() : Returns the last page written to
00025                 GetPage() : Returns the last page read
00026                 ReadByte()
00027                 ReadInt()
00028                 ReadLong()
00029                 
00030         Properties:
00031                         
00032 */
00033 
00034 extern "C" {
00035   // AVR LibC Includes
00036   #include <inttypes.h>
00037   #include <avr/interrupt.h>
00038   #include "WConstants.h"
00039 }
00040 
00041 #include "DataFlash.h"
00042 
00043 #define OVERWRITE_DATA 0 // 0: When reach the end page stop, 1: Start overwritten from page 1
00044 
00045 // *** INTERNAL FUNCTIONS ***
00046 unsigned char dataflash_SPI_transfer(unsigned char output)
00047 {
00048   SPDR = output;                     // Start the transmission
00049   while (!(SPSR & (1<<SPIF)));       // Wait the end of the transmission
00050   return SPDR; 
00051 }
00052 
00053 void dataflash_CS_inactive()
00054 {
00055   digitalWrite(DF_SLAVESELECT,HIGH); //disable device
00056 }
00057 
00058 void dataflash_CS_active()
00059 {
00060   digitalWrite(DF_SLAVESELECT,LOW); //enable device
00061 }
00062 
00063 // Constructors ////////////////////////////////////////////////////////////////
00064 DataFlash_Class::DataFlash_Class()
00065 {
00066 }
00067 
00068 // Public Methods //////////////////////////////////////////////////////////////
00069 void DataFlash_Class::Init(void)
00070 {
00071   byte tmp;
00072   
00073   pinMode(DF_DATAOUT, OUTPUT);
00074   pinMode(DF_DATAIN, INPUT);
00075   pinMode(DF_SPICLOCK,OUTPUT);
00076   pinMode(DF_SLAVESELECT,OUTPUT);
00077   #if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
00078         pinMode(DF_RESET,OUTPUT);
00079         // Reset the chip
00080         digitalWrite(DF_RESET,LOW);
00081         delay(1);
00082         digitalWrite(DF_RESET,HIGH);
00083   #endif
00084 
00085   df_Read_END=false;
00086   
00087   dataflash_CS_inactive();     //disable device
00088   
00089   // Setup SPI  Master, Mode 3, fosc/4 = 4MHz
00090   SPCR = (1<<SPE)|(1<<MSTR)|(1<<CPHA)|(1<<CPOL);
00091   // Setup SPI  Master, Mode 3, 2MHz
00092   //SPCR = (1<<SPE)|(1<<MSTR)|(1<<CPHA)|(1<<CPOL)|(1<<SPR0);
00093   //SPSR = (1<<SPI2X);
00094   // Cleanup registers...
00095   tmp=SPSR;
00096   tmp=SPDR;
00097 }
00098 
00099 // This function is mainly to test the device
00100 void DataFlash_Class::ReadManufacturerID()
00101 {
00102   byte tmp;
00103   
00104   dataflash_CS_inactive();    // Reset dataflash command decoder
00105   dataflash_CS_active();     
00106  
00107   // Read manufacturer and ID command...
00108   dataflash_SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
00109 
00110   df_manufacturer = dataflash_SPI_transfer(0xff);
00111   df_device_0 = dataflash_SPI_transfer(0xff);
00112   df_device_1 = dataflash_SPI_transfer(0xff);
00113   tmp = dataflash_SPI_transfer(0xff);
00114 }
00115 
00116 // Read the status of the DataFlash
00117 byte DataFlash_Class::ReadStatus()
00118 { 
00119   byte tmp;
00120   
00121   dataflash_CS_inactive();    // Reset dataflash command decoder
00122   dataflash_CS_active();     
00123  
00124   // Read status command
00125   dataflash_SPI_transfer(DF_STATUS_REGISTER_READ);
00126   tmp = dataflash_SPI_transfer(0x00);
00127   return(tmp&0x80);  // We only want to extract the READY/BUSY bit
00128 }
00129 
00130 // Wait until DataFlash is in ready state...
00131 void DataFlash_Class::WaitReady()
00132 {
00133   while(!ReadStatus());
00134 }
00135 
00136 void DataFlash_Class::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
00137 {
00138   dataflash_CS_inactive();      
00139   dataflash_CS_active();                
00140   if (BufferNum==1)                             
00141     dataflash_SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
00142   else
00143     dataflash_SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);               
00144   dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));        
00145   dataflash_SPI_transfer((unsigned char)(PageAdr << 2));        
00146   dataflash_SPI_transfer(0x00); // don´t care bytes                    
00147 
00148   dataflash_CS_inactive();      //initiate the transfer
00149   dataflash_CS_active();
00150   
00151   while(!ReadStatus());  //monitor the status register, wait until busy-flag is high
00152 }
00153 
00154 void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
00155 {
00156   dataflash_CS_inactive();     // Reset dataflash command decoder
00157   dataflash_CS_active();
00158   
00159   if (BufferNum==1)     
00160     dataflash_SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
00161   else
00162     dataflash_SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
00163   dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));        
00164   dataflash_SPI_transfer((unsigned char)(PageAdr << 2));        
00165   dataflash_SPI_transfer(0x00); // don´t care bytes                    
00166 
00167   dataflash_CS_inactive();      //initiate the transfer
00168   dataflash_CS_active();
00169   
00170   // Check if we need to wait to write the buffer to memory or we can continue...
00171   if (wait)
00172         while(!ReadStatus());  //monitor the status register, wait until busy-flag is high
00173 }
00174 
00175 void DataFlash_Class::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
00176 {
00177   dataflash_CS_inactive();   // Reset dataflash command decoder
00178   dataflash_CS_active();
00179   
00180   if (BufferNum==1)     
00181     dataflash_SPI_transfer(DF_BUFFER_1_WRITE);
00182   else
00183     dataflash_SPI_transfer(DF_BUFFER_2_WRITE);
00184   dataflash_SPI_transfer(0x00);                          //don't cares
00185   dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8));  //upper part of internal buffer address
00186   dataflash_SPI_transfer((unsigned char)(IntPageAdr));   //lower part of internal buffer address
00187   dataflash_SPI_transfer(Data);                          //write data byte
00188 }
00189   
00190 unsigned char DataFlash_Class::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
00191 {
00192   byte tmp;
00193   
00194   dataflash_CS_inactive();   // Reset dataflash command decoder
00195   dataflash_CS_active();
00196   
00197   if (BufferNum==1)     
00198     dataflash_SPI_transfer(DF_BUFFER_1_READ);
00199   else
00200     dataflash_SPI_transfer(DF_BUFFER_2_READ);
00201   dataflash_SPI_transfer(0x00);                          //don't cares
00202   dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8));  //upper part of internal buffer address
00203   dataflash_SPI_transfer((unsigned char)(IntPageAdr));   //lower part of internal buffer address
00204   dataflash_SPI_transfer(0x00);                            //don't cares
00205   tmp = dataflash_SPI_transfer(0x00);                    //read data byte
00206   
00207   return (tmp);
00208 }
00209 // *** END OF INTERNAL FUNCTIONS ***
00210 
00211 void DataFlash_Class::PageErase (unsigned int PageAdr)
00212 {
00213   dataflash_CS_inactive();                                                                                                                              //make sure to toggle CS signal in order
00214   dataflash_CS_active();                                                                                                                                //to reset Dataflash command decoder
00215   dataflash_SPI_transfer(DF_PAGE_ERASE);   // Command
00216   dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));        //upper part of page address
00217   dataflash_SPI_transfer((unsigned char)(PageAdr << 2));        //lower part of page address and MSB of int.page adr.
00218   dataflash_SPI_transfer(0x00);            // "dont cares"
00219   dataflash_CS_inactive();               //initiate flash page erase
00220   dataflash_CS_active();
00221   while(!ReadStatus());
00222 }
00223 
00224 // *** DATAFLASH PUBLIC FUNCTIONS ***
00225 void DataFlash_Class::StartWrite(int PageAdr)
00226 {
00227   df_BufferNum=1;
00228   df_BufferIdx=0;
00229   df_PageAdr=PageAdr;
00230   df_Stop_Write=0;
00231   WaitReady();
00232 }
00233 
00234 void DataFlash_Class::WriteByte(byte data)
00235 {
00236   if (!df_Stop_Write)
00237     {
00238     BufferWrite(df_BufferNum,df_BufferIdx,data);
00239     df_BufferIdx++;
00240     if (df_BufferIdx >= 512)  // End of buffer?
00241       {
00242       df_BufferIdx=0;
00243           BufferToPage(df_BufferNum,df_PageAdr,0);  // Write Buffer to memory, NO WAIT
00244       df_PageAdr++;
00245           if (OVERWRITE_DATA==1)
00246             {
00247         if (df_PageAdr>=4096)  // If we reach the end of the memory, start from the begining
00248                   df_PageAdr = 1;
00249             }
00250       else
00251             {
00252         if (df_PageAdr>=4096)  // If we reach the end of the memory, stop here
00253                   df_Stop_Write=1;
00254             }
00255 
00256       if (df_BufferNum==1)  // Change buffer to continue writing...
00257         df_BufferNum=2;
00258       else
00259         df_BufferNum=1;
00260       }
00261     }
00262 }
00263 
00264 void DataFlash_Class::WriteInt(int data)
00265 {
00266   WriteByte(data>>8);   // High byte
00267   WriteByte(data&0xFF); // Low byte
00268 }
00269 
00270 void DataFlash_Class::WriteLong(long data)
00271 {
00272   WriteByte(data>>24);   // First byte
00273   WriteByte(data>>16);
00274   WriteByte(data>>8);
00275   WriteByte(data&0xFF);  // Last byte
00276 }
00277 
00278 // Get the last page written to
00279 int DataFlash_Class::GetWritePage() 
00280 {
00281   return(df_PageAdr);
00282 }
00283 
00284 // Get the last page read
00285 int DataFlash_Class::GetPage() 
00286 {
00287   return(df_Read_PageAdr-1);
00288 }
00289 
00290 void DataFlash_Class::StartRead(int PageAdr)
00291 {
00292   df_Read_BufferNum=1;
00293   df_Read_BufferIdx=0;
00294   df_Read_PageAdr=PageAdr;
00295   WaitReady();
00296   PageToBuffer(df_Read_BufferNum,df_Read_PageAdr);  // Write Memory page to buffer
00297   df_Read_PageAdr++;
00298 }
00299 
00300 byte DataFlash_Class::ReadByte()
00301 {
00302   byte result;
00303   
00304   WaitReady();
00305   result = BufferRead(df_Read_BufferNum,df_Read_BufferIdx);
00306   df_Read_BufferIdx++;
00307   if (df_Read_BufferIdx >= 512)  // End of buffer?
00308     {
00309     df_Read_BufferIdx=0;
00310     PageToBuffer(df_Read_BufferNum,df_Read_PageAdr);  // Write memory page to Buffer
00311     df_Read_PageAdr++;
00312     if (df_Read_PageAdr>=4096)  // If we reach the end of the memory, start from the begining
00313       {
00314       df_Read_PageAdr = 0;
00315       df_Read_END = true;
00316       }
00317     }
00318   return result;
00319 }
00320 
00321 int DataFlash_Class::ReadInt()
00322 {
00323   int result;
00324   
00325   result = ReadByte();               // High byte
00326   result = (result<<8) | ReadByte(); // Low byte
00327   return result;
00328 }
00329 
00330 long DataFlash_Class::ReadLong()
00331 {
00332   long result;
00333   
00334   result = ReadByte();               // First byte
00335   result = (result<<8) | ReadByte(); 
00336   result = (result<<8) | ReadByte();
00337   result = (result<<8) | ReadByte(); // Last byte
00338   return result;
00339 }
00340 
00341 // make one instance for the user to use
00342 DataFlash_Class DataFlash;

Generated for ArduPilot Libraries by doxygen