Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 extern "C" {
00035
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
00046 unsigned char dataflash_SPI_transfer(unsigned char output)
00047 {
00048 SPDR = output;
00049 while (!(SPSR & (1<<SPIF)));
00050 return SPDR;
00051 }
00052
00053 void dataflash_CS_inactive()
00054 {
00055 digitalWrite(DF_SLAVESELECT,HIGH);
00056 }
00057
00058 void dataflash_CS_active()
00059 {
00060 digitalWrite(DF_SLAVESELECT,LOW);
00061 }
00062
00063
00064 DataFlash_Class::DataFlash_Class()
00065 {
00066 }
00067
00068
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
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();
00088
00089
00090 SPCR = (1<<SPE)|(1<<MSTR)|(1<<CPHA)|(1<<CPOL);
00091
00092
00093
00094
00095 tmp=SPSR;
00096 tmp=SPDR;
00097 }
00098
00099
00100 void DataFlash_Class::ReadManufacturerID()
00101 {
00102 byte tmp;
00103
00104 dataflash_CS_inactive();
00105 dataflash_CS_active();
00106
00107
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
00117 byte DataFlash_Class::ReadStatus()
00118 {
00119 byte tmp;
00120
00121 dataflash_CS_inactive();
00122 dataflash_CS_active();
00123
00124
00125 dataflash_SPI_transfer(DF_STATUS_REGISTER_READ);
00126 tmp = dataflash_SPI_transfer(0x00);
00127 return(tmp&0x80);
00128 }
00129
00130
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);
00147
00148 dataflash_CS_inactive();
00149 dataflash_CS_active();
00150
00151 while(!ReadStatus());
00152 }
00153
00154 void DataFlash_Class::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
00155 {
00156 dataflash_CS_inactive();
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);
00166
00167 dataflash_CS_inactive();
00168 dataflash_CS_active();
00169
00170
00171 if (wait)
00172 while(!ReadStatus());
00173 }
00174
00175 void DataFlash_Class::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
00176 {
00177 dataflash_CS_inactive();
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);
00185 dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8));
00186 dataflash_SPI_transfer((unsigned char)(IntPageAdr));
00187 dataflash_SPI_transfer(Data);
00188 }
00189
00190 unsigned char DataFlash_Class::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
00191 {
00192 byte tmp;
00193
00194 dataflash_CS_inactive();
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);
00202 dataflash_SPI_transfer((unsigned char)(IntPageAdr>>8));
00203 dataflash_SPI_transfer((unsigned char)(IntPageAdr));
00204 dataflash_SPI_transfer(0x00);
00205 tmp = dataflash_SPI_transfer(0x00);
00206
00207 return (tmp);
00208 }
00209
00210
00211 void DataFlash_Class::PageErase (unsigned int PageAdr)
00212 {
00213 dataflash_CS_inactive();
00214 dataflash_CS_active();
00215 dataflash_SPI_transfer(DF_PAGE_ERASE);
00216 dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));
00217 dataflash_SPI_transfer((unsigned char)(PageAdr << 2));
00218 dataflash_SPI_transfer(0x00);
00219 dataflash_CS_inactive();
00220 dataflash_CS_active();
00221 while(!ReadStatus());
00222 }
00223
00224
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)
00241 {
00242 df_BufferIdx=0;
00243 BufferToPage(df_BufferNum,df_PageAdr,0);
00244 df_PageAdr++;
00245 if (OVERWRITE_DATA==1)
00246 {
00247 if (df_PageAdr>=4096)
00248 df_PageAdr = 1;
00249 }
00250 else
00251 {
00252 if (df_PageAdr>=4096)
00253 df_Stop_Write=1;
00254 }
00255
00256 if (df_BufferNum==1)
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);
00267 WriteByte(data&0xFF);
00268 }
00269
00270 void DataFlash_Class::WriteLong(long data)
00271 {
00272 WriteByte(data>>24);
00273 WriteByte(data>>16);
00274 WriteByte(data>>8);
00275 WriteByte(data&0xFF);
00276 }
00277
00278
00279 int DataFlash_Class::GetWritePage()
00280 {
00281 return(df_PageAdr);
00282 }
00283
00284
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);
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)
00308 {
00309 df_Read_BufferIdx=0;
00310 PageToBuffer(df_Read_BufferNum,df_Read_PageAdr);
00311 df_Read_PageAdr++;
00312 if (df_Read_PageAdr>=4096)
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();
00326 result = (result<<8) | ReadByte();
00327 return result;
00328 }
00329
00330 long DataFlash_Class::ReadLong()
00331 {
00332 long result;
00333
00334 result = ReadByte();
00335 result = (result<<8) | ReadByte();
00336 result = (result<<8) | ReadByte();
00337 result = (result<<8) | ReadByte();
00338 return result;
00339 }
00340
00341
00342 DataFlash_Class DataFlash;