|
|
|
@ -1,36 +1,36 @@
@@ -1,36 +1,36 @@
|
|
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
/*
|
|
|
|
|
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: |
|
|
|
|
|
|
|
|
|
*/ |
|
|
|
|
* 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" |
|
|
|
@ -97,13 +97,13 @@ void DataFlash_APM1::Init(void)
@@ -97,13 +97,13 @@ void DataFlash_APM1::Init(void)
|
|
|
|
|
pinMode(DF_DATAIN, INPUT); |
|
|
|
|
pinMode(DF_SPICLOCK,OUTPUT); |
|
|
|
|
pinMode(DF_SLAVESELECT,OUTPUT); |
|
|
|
|
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) |
|
|
|
|
#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 |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
dataflash_CS_inactive(); //disable device
|
|
|
|
|
|
|
|
|
@ -176,7 +176,7 @@ uint16_t DataFlash_APM1::PageSize()
@@ -176,7 +176,7 @@ uint16_t DataFlash_APM1::PageSize()
|
|
|
|
|
// Wait until DataFlash is in ready state...
|
|
|
|
|
void DataFlash_APM1::WaitReady() |
|
|
|
|
{ |
|
|
|
|
while(!ReadStatus()); |
|
|
|
|
while(!ReadStatus()) ; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr) |
|
|
|
@ -188,7 +188,7 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
@@ -188,7 +188,7 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
|
|
|
|
else |
|
|
|
|
SPI.transfer(DF_TRANSFER_PAGE_TO_BUFFER_2); |
|
|
|
|
|
|
|
|
|
if(df_PageSize==512){ |
|
|
|
|
if(df_PageSize==512) { |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr >> 7)); |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr << 1)); |
|
|
|
|
}else{ |
|
|
|
@ -200,7 +200,7 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
@@ -200,7 +200,7 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
|
|
|
|
dataflash_CS_inactive(); //initiate the transfer
|
|
|
|
|
dataflash_CS_active(); |
|
|
|
|
|
|
|
|
|
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
|
|
|
|
while(!ReadStatus()) ; //monitor the status register, wait until busy-flag is high
|
|
|
|
|
|
|
|
|
|
dataflash_CS_inactive(); |
|
|
|
|
|
|
|
|
@ -215,7 +215,7 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
@@ -215,7 +215,7 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
|
|
|
|
|
else |
|
|
|
|
SPI.transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE); |
|
|
|
|
|
|
|
|
|
if(df_PageSize==512){ |
|
|
|
|
if(df_PageSize==512) { |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr >> 7)); |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr << 1)); |
|
|
|
|
}else{ |
|
|
|
@ -229,7 +229,7 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
@@ -229,7 +229,7 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
|
|
|
|
|
|
|
|
|
|
// 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
|
|
|
|
|
while(!ReadStatus()) ; //monitor the status register, wait until busy-flag is high
|
|
|
|
|
|
|
|
|
|
dataflash_CS_inactive(); //deactivate dataflash command decoder
|
|
|
|
|
} |
|
|
|
@ -277,7 +277,7 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
@@ -277,7 +277,7 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
|
|
|
|
dataflash_CS_active(); // activate dataflash command decoder
|
|
|
|
|
SPI.transfer(DF_PAGE_ERASE); // Command
|
|
|
|
|
|
|
|
|
|
if(df_PageSize==512){ |
|
|
|
|
if(df_PageSize==512) { |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr >> 7)); |
|
|
|
|
SPI.transfer((unsigned char)(PageAdr << 1)); |
|
|
|
|
}else{ |
|
|
|
@ -288,7 +288,7 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
@@ -288,7 +288,7 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
|
|
|
|
SPI.transfer(0x00); // "dont cares"
|
|
|
|
|
dataflash_CS_inactive(); //initiate flash page erase
|
|
|
|
|
dataflash_CS_active(); |
|
|
|
|
while(!ReadStatus()); |
|
|
|
|
while(!ReadStatus()) ; |
|
|
|
|
|
|
|
|
|
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
|
|
|
|
} |
|
|
|
@ -310,7 +310,7 @@ void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
@@ -310,7 +310,7 @@ void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
|
|
|
|
|
SPI.transfer(0x00); // "dont cares"
|
|
|
|
|
dataflash_CS_inactive(); //initiate flash page erase
|
|
|
|
|
dataflash_CS_active(); |
|
|
|
|
while(!ReadStatus()); |
|
|
|
|
while(!ReadStatus()) ; |
|
|
|
|
|
|
|
|
|
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
|
|
|
|
} |
|
|
|
|