mirror of https://github.com/ArduPilot/ardupilot
APM1 Dataflash update
My data flash would never erase, this fixed it.
This commit is contained in:
parent
7fab9d940f
commit
efeffc1c4b
|
@ -1,8 +1,8 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
/*
|
/*
|
||||||
* DataFlash_APM1.cpp - DataFlash log library for AT45DB161
|
* DataFlash_APM1.cpp - DataFlash log library for AT45DB161
|
||||||
* Code by Jordi Munoz and Jose Julio. DIYDrones.com
|
* 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 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
|
* This library is free software; you can redistribute it and/or
|
||||||
* modify it under the terms of the GNU Lesser General Public
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
|
@ -32,10 +32,34 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdint.h>
|
extern "C" {
|
||||||
#include "DataFlash.h"
|
// AVR LibC Includes
|
||||||
|
#include <inttypes.h>
|
||||||
|
#include <avr/interrupt.h>
|
||||||
|
}
|
||||||
|
#include <FastSerial.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
|
#include "Arduino.h"
|
||||||
|
#else
|
||||||
|
#include "WConstants.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <AP_Semaphore.h> // for removing conflict with optical flow sensor on SPI3 bus
|
||||||
|
#include "DataFlash_APM2.h"
|
||||||
|
|
||||||
|
///*
|
||||||
|
#define ENABLE_FASTSERIAL_DEBUG
|
||||||
|
#ifdef ENABLE_FASTSERIAL_DEBUG
|
||||||
|
# define serialDebug(fmt, args...) if (FastSerial::getInitialized(0)) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args); delay(0); } while(0)
|
||||||
|
#else
|
||||||
|
# define serialDebug(fmt, args...)
|
||||||
|
#endif
|
||||||
|
//*/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// flash size
|
// flash size
|
||||||
#define DF_LAST_PAGE 4096
|
#define DF_LAST_PAGE 4096
|
||||||
|
|
||||||
|
@ -73,13 +97,15 @@
|
||||||
#define DF_CHIP_ERASE_2 0x80
|
#define DF_CHIP_ERASE_2 0x80
|
||||||
#define DF_CHIP_ERASE_3 0x9A
|
#define DF_CHIP_ERASE_3 0x9A
|
||||||
|
|
||||||
|
|
||||||
// *** INTERNAL FUNCTIONS ***
|
// *** INTERNAL FUNCTIONS ***
|
||||||
|
|
||||||
unsigned char DataFlash_APM1::SPI_transfer(unsigned char data)
|
unsigned char DataFlash_APM1::SPI_transfer(unsigned char data)
|
||||||
{
|
{
|
||||||
unsigned char retval;
|
unsigned char retval;
|
||||||
|
|
||||||
// get spi semaphore if required. if failed to get semaphore then just quietly fail
|
// get spi semaphore if required. if failed to get semaphore then
|
||||||
|
// just quietly fail
|
||||||
if ( _spi_semaphore != NULL) {
|
if ( _spi_semaphore != NULL) {
|
||||||
if( !_spi_semaphore->get(this) ) {
|
if( !_spi_semaphore->get(this) ) {
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -97,20 +123,24 @@ unsigned char DataFlash_APM1::SPI_transfer(unsigned char data)
|
||||||
return retval;
|
return retval;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// disable device
|
||||||
void dataflash_CS_inactive()
|
void DataFlash_APM1::CS_inactive()
|
||||||
{
|
{
|
||||||
digitalWrite(DF_SLAVESELECT,HIGH); //disable device
|
digitalWrite(DF_SLAVESELECT,HIGH);
|
||||||
}
|
}
|
||||||
|
|
||||||
void dataflash_CS_active()
|
// enable device
|
||||||
|
void DataFlash_APM1::CS_active()
|
||||||
{
|
{
|
||||||
digitalWrite(DF_SLAVESELECT,LOW); //enable device
|
digitalWrite(DF_SLAVESELECT,LOW);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void DataFlash_APM1::Init(void)
|
void DataFlash_APM1::Init(void)
|
||||||
{
|
{
|
||||||
|
// init to zero
|
||||||
|
df_NumPages = 0;
|
||||||
|
|
||||||
pinMode(DF_DATAOUT, OUTPUT);
|
pinMode(DF_DATAOUT, OUTPUT);
|
||||||
pinMode(DF_DATAIN, INPUT);
|
pinMode(DF_DATAIN, INPUT);
|
||||||
pinMode(DF_SPICLOCK,OUTPUT);
|
pinMode(DF_SPICLOCK,OUTPUT);
|
||||||
|
@ -123,7 +153,8 @@ void DataFlash_APM1::Init(void)
|
||||||
digitalWrite(DF_RESET,HIGH);
|
digitalWrite(DF_RESET,HIGH);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
dataflash_CS_inactive(); //disable device
|
// disable device
|
||||||
|
CS_inactive();
|
||||||
|
|
||||||
// Setup SPI Master, Mode 3, fosc/4 = 4MHz
|
// Setup SPI Master, Mode 3, fosc/4 = 4MHz
|
||||||
SPI.begin();
|
SPI.begin();
|
||||||
|
@ -131,8 +162,8 @@ void DataFlash_APM1::Init(void)
|
||||||
SPI.setDataMode(SPI_MODE3);
|
SPI.setDataMode(SPI_MODE3);
|
||||||
SPI.setClockDivider(SPI_CLOCK_DIV2);
|
SPI.setClockDivider(SPI_CLOCK_DIV2);
|
||||||
|
|
||||||
// get page size: 512 or 528
|
// get page size: 512 or 528 (by default: 528)
|
||||||
df_PageSize=PageSize();
|
df_PageSize = PageSize();
|
||||||
|
|
||||||
// the last page is reserved for config information
|
// the last page is reserved for config information
|
||||||
df_NumPages = DF_LAST_PAGE - 1;
|
df_NumPages = DF_LAST_PAGE - 1;
|
||||||
|
@ -141,21 +172,23 @@ void DataFlash_APM1::Init(void)
|
||||||
// This function is mainly to test the device
|
// This function is mainly to test the device
|
||||||
void DataFlash_APM1::ReadManufacturerID()
|
void DataFlash_APM1::ReadManufacturerID()
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
// Read manufacturer and ID command...
|
// Read manufacturer and ID command...
|
||||||
SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
|
SPI_transfer(DF_READ_MANUFACTURER_AND_DEVICE_ID);
|
||||||
|
|
||||||
df_manufacturer = SPI_transfer(0xff);
|
df_manufacturer = SPI_transfer(0xff);
|
||||||
df_device = SPI_transfer(0xff);
|
df_device = SPI_transfer(0xff);
|
||||||
df_device = (df_device<<8) | SPI_transfer(0xff);
|
df_device = (df_device << 8) | SPI_transfer(0xff);
|
||||||
SPI_transfer(0xff);
|
SPI_transfer(0xff);
|
||||||
|
|
||||||
dataflash_CS_inactive(); // Reset dataflash command decoder
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// This function return 1 if Card is inserted on SD slot
|
||||||
bool DataFlash_APM1::CardInserted(void)
|
bool DataFlash_APM1::CardInserted()
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -165,13 +198,15 @@ byte DataFlash_APM1::ReadStatusReg()
|
||||||
{
|
{
|
||||||
byte tmp;
|
byte tmp;
|
||||||
|
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
// Read status command
|
// Read status command
|
||||||
SPI_transfer(DF_STATUS_REGISTER_READ);
|
SPI_transfer(DF_STATUS_REGISTER_READ);
|
||||||
tmp = SPI_transfer(0x00); // We only want to extract the READY/BUSY bit
|
tmp = SPI_transfer(0x00); // We only want to extract the READY/BUSY bit
|
||||||
|
|
||||||
dataflash_CS_inactive(); // Reset dataflash command decoder
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
|
|
||||||
return tmp;
|
return tmp;
|
||||||
}
|
}
|
||||||
|
@ -183,14 +218,12 @@ byte DataFlash_APM1::ReadStatus()
|
||||||
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
|
return(ReadStatusReg()&0x80); // We only want to extract the READY/BUSY bit
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline
|
inline
|
||||||
uint16_t DataFlash_APM1::PageSize()
|
uint16_t DataFlash_APM1::PageSize()
|
||||||
{
|
{
|
||||||
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
|
return(528-((ReadStatusReg()&0x01) << 4)); // if first bit 1 trhen 512 else 528 bytes
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Wait until DataFlash is in ready state...
|
// Wait until DataFlash is in ready state...
|
||||||
void DataFlash_APM1::WaitReady()
|
void DataFlash_APM1::WaitReady()
|
||||||
{
|
{
|
||||||
|
@ -199,7 +232,8 @@ void DataFlash_APM1::WaitReady()
|
||||||
|
|
||||||
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
if (BufferNum==1)
|
if (BufferNum==1)
|
||||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
|
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_1);
|
||||||
|
@ -215,18 +249,20 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||||
}
|
}
|
||||||
SPI_transfer(0x00); // don´t care bytes
|
SPI_transfer(0x00); // don´t care bytes
|
||||||
|
|
||||||
dataflash_CS_inactive(); //initiate the transfer
|
//initiate the transfer
|
||||||
dataflash_CS_active();
|
CS_inactive();
|
||||||
|
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();
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
if (BufferNum==1)
|
if (BufferNum==1)
|
||||||
SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
|
SPI_transfer(DF_BUFFER_1_TO_PAGE_WITH_ERASE);
|
||||||
|
@ -242,49 +278,57 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
|
||||||
}
|
}
|
||||||
SPI_transfer(0x00); // don´t care bytes
|
SPI_transfer(0x00); // don´t care bytes
|
||||||
|
|
||||||
dataflash_CS_inactive(); //initiate the transfer
|
//initiate the transfer
|
||||||
dataflash_CS_active();
|
CS_inactive();
|
||||||
|
CS_active();
|
||||||
|
|
||||||
// Check if we need to wait to write the buffer to memory or we can continue...
|
// Check if we need to wait to write the buffer to memory or we can continue...
|
||||||
if (wait)
|
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
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
if (BufferNum==1)
|
if (BufferNum==1)
|
||||||
SPI_transfer(DF_BUFFER_1_WRITE);
|
SPI_transfer(DF_BUFFER_1_WRITE);
|
||||||
else
|
else
|
||||||
SPI_transfer(DF_BUFFER_2_WRITE);
|
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
|
SPI_transfer(0x00); // don't care
|
||||||
|
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
|
||||||
|
|
||||||
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
||||||
{
|
{
|
||||||
byte tmp;
|
byte tmp;
|
||||||
|
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
if (BufferNum==1)
|
if (BufferNum==1)
|
||||||
SPI_transfer(DF_BUFFER_1_READ);
|
SPI_transfer(DF_BUFFER_1_READ);
|
||||||
else
|
else
|
||||||
SPI_transfer(DF_BUFFER_2_READ);
|
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
|
SPI_transfer(0x00);
|
||||||
|
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
|
||||||
|
|
||||||
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
|
|
||||||
return (tmp);
|
return (tmp);
|
||||||
}
|
}
|
||||||
|
@ -292,8 +336,11 @@ unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, uint16_t IntP
|
||||||
|
|
||||||
void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
SPI_transfer(DF_PAGE_ERASE); // Command
|
CS_active();
|
||||||
|
|
||||||
|
// Send page erase command
|
||||||
|
SPI_transfer(DF_PAGE_ERASE);
|
||||||
|
|
||||||
if(df_PageSize==512) {
|
if(df_PageSize==512) {
|
||||||
SPI_transfer((unsigned char)(PageAdr >> 7));
|
SPI_transfer((unsigned char)(PageAdr >> 7));
|
||||||
|
@ -303,54 +350,76 @@ void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
||||||
SPI_transfer((unsigned char)(PageAdr << 2));
|
SPI_transfer((unsigned char)(PageAdr << 2));
|
||||||
}
|
}
|
||||||
|
|
||||||
SPI_transfer(0x00); // "dont cares"
|
SPI_transfer(0x00);
|
||||||
dataflash_CS_inactive(); //initiate flash page erase
|
|
||||||
dataflash_CS_active();
|
//initiate flash page erase
|
||||||
|
CS_inactive();
|
||||||
|
CS_active();
|
||||||
while(!ReadStatus()) ;
|
while(!ReadStatus()) ;
|
||||||
|
|
||||||
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
|
void DataFlash_APM1::BlockErase (uint16_t BlockAdr)
|
||||||
{
|
{
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
// activate dataflash command decoder
|
||||||
SPI_transfer(DF_BLOCK_ERASE); // Command
|
CS_active();
|
||||||
|
|
||||||
|
// Send block erase command
|
||||||
|
SPI_transfer(DF_BLOCK_ERASE);
|
||||||
|
|
||||||
|
/*
|
||||||
if (df_PageSize==512) {
|
if (df_PageSize==512) {
|
||||||
SPI_transfer((unsigned char)(BlockAdr >> 3));
|
SPI_transfer((unsigned char)(BlockAdr >> 3));
|
||||||
SPI_transfer((unsigned char)(BlockAdr << 5));
|
SPI_transfer((unsigned char)(BlockAdr << 5));
|
||||||
} else {
|
} else {
|
||||||
SPI_transfer((unsigned char)(BlockAdr >> 4));
|
SPI_transfer((unsigned char)(BlockAdr >> 4));
|
||||||
SPI_transfer((unsigned char)(BlockAdr << 4));
|
SPI_transfer((unsigned char)(BlockAdr << 4));
|
||||||
|
}*/
|
||||||
|
|
||||||
|
if (df_PageSize==512) {
|
||||||
|
SPI_transfer((unsigned char)(BlockAdr >> 4));
|
||||||
|
SPI_transfer((unsigned char)(BlockAdr << 4));
|
||||||
|
} else {
|
||||||
|
SPI_transfer((unsigned char)(BlockAdr >> 3));
|
||||||
|
SPI_transfer((unsigned char)(BlockAdr << 5));
|
||||||
}
|
}
|
||||||
|
|
||||||
SPI_transfer(0x00); // "dont cares"
|
SPI_transfer(0x00);
|
||||||
dataflash_CS_inactive(); //initiate flash page erase
|
serialDebug("BL Erase, %d\n", BlockAdr);
|
||||||
dataflash_CS_active();
|
|
||||||
|
//initiate flash page erase
|
||||||
|
CS_inactive();
|
||||||
|
CS_active();
|
||||||
while(!ReadStatus()) ;
|
while(!ReadStatus()) ;
|
||||||
|
|
||||||
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void DataFlash_APM1::ChipErase(void (*delay_cb)(unsigned long))
|
void DataFlash_APM1::ChipErase(void (*delay_cb)(unsigned long))
|
||||||
{
|
{
|
||||||
|
//serialDebug("Chip Erase\n");
|
||||||
|
|
||||||
|
// activate dataflash command decoder
|
||||||
|
CS_active();
|
||||||
|
|
||||||
dataflash_CS_active(); // activate dataflash command decoder
|
|
||||||
// opcodes for chip erase
|
// opcodes for chip erase
|
||||||
SPI_transfer(DF_CHIP_ERASE_0);
|
SPI_transfer(DF_CHIP_ERASE_0);
|
||||||
SPI_transfer(DF_CHIP_ERASE_1);
|
SPI_transfer(DF_CHIP_ERASE_1);
|
||||||
SPI_transfer(DF_CHIP_ERASE_2);
|
SPI_transfer(DF_CHIP_ERASE_2);
|
||||||
SPI_transfer(DF_CHIP_ERASE_3);
|
SPI_transfer(DF_CHIP_ERASE_3);
|
||||||
|
|
||||||
dataflash_CS_inactive(); //initiate flash page erase
|
//initiate flash page erase
|
||||||
dataflash_CS_active();
|
CS_inactive();
|
||||||
while (!ReadStatus()) {
|
CS_active();
|
||||||
|
|
||||||
|
while(!ReadStatus()) {
|
||||||
delay_cb(1);
|
delay_cb(1);
|
||||||
}
|
}
|
||||||
|
|
||||||
dataflash_CS_inactive(); // deactivate dataflash command decoder
|
// release SPI bus for use by other sensors
|
||||||
|
CS_inactive();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
/* ************************************************************ */
|
/* ************************************************************ */
|
||||||
/* Test for DataFlash Log library */
|
/* DataFlash_APM1 Log library */
|
||||||
/* ************************************************************ */
|
/* ************************************************************ */
|
||||||
#ifndef __DATAFLASH_APM1_H__
|
#ifndef __DATAFLASH_APM1_H__
|
||||||
#define __DATAFLASH_APM1_H__
|
#define __DATAFLASH_APM1_H__
|
||||||
|
@ -19,6 +19,8 @@ private:
|
||||||
unsigned char ReadStatusReg();
|
unsigned char ReadStatusReg();
|
||||||
unsigned char ReadStatus();
|
unsigned char ReadStatus();
|
||||||
uint16_t PageSize();
|
uint16_t PageSize();
|
||||||
|
void CS_inactive();
|
||||||
|
void CS_active();
|
||||||
void PageErase (uint16_t PageAdr);
|
void PageErase (uint16_t PageAdr);
|
||||||
void BlockErase (uint16_t BlockAdr);
|
void BlockErase (uint16_t BlockAdr);
|
||||||
void ChipErase(void (*delay_cb)(unsigned long));
|
void ChipErase(void (*delay_cb)(unsigned long));
|
||||||
|
@ -30,7 +32,7 @@ public:
|
||||||
DataFlash_APM1(AP_Semaphore* spi_semaphore = NULL) : _spi_semaphore(spi_semaphore) {}
|
DataFlash_APM1(AP_Semaphore* spi_semaphore = NULL) : _spi_semaphore(spi_semaphore) {}
|
||||||
void Init();
|
void Init();
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
bool CardInserted(void);
|
bool CardInserted();
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __DATAFLASH_APM1_H__
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue