mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/DataFlash/DataFlash_APM2.cpp
This commit is contained in:
parent
15d8ba45e3
commit
eb9d6b259b
|
@ -1,41 +1,41 @@
|
||||||
/// -*- 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_APM2.cpp - DataFlash log library for AT45DB321D
|
* DataFlash_APM2.cpp - DataFlash log library for AT45DB321D
|
||||||
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
* 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 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
|
||||||
License as published by the Free Software Foundation; either
|
* License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
|
*
|
||||||
Dataflash library for AT45DB321D flash memory
|
* Dataflash library for AT45DB321D flash memory
|
||||||
Memory organization : 8192 pages of 512 bytes or 528 bytes
|
* Memory organization : 8192 pages of 512 bytes or 528 bytes
|
||||||
|
*
|
||||||
Maximun write bandwidth : 512 bytes in 14ms
|
* 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
|
* This code is written so the master never has to wait to write the data on the eeprom
|
||||||
|
*
|
||||||
Methods:
|
* Methods:
|
||||||
Init() : Library initialization (SPI initialization)
|
* Init() : Library initialization (SPI initialization)
|
||||||
StartWrite(page) : Start a write session. page=start page.
|
* StartWrite(page) : Start a write session. page=start page.
|
||||||
WriteByte(data) : Write a byte
|
* WriteByte(data) : Write a byte
|
||||||
WriteInt(data) : Write an integer (2 bytes)
|
* WriteInt(data) : Write an integer (2 bytes)
|
||||||
WriteLong(data) : Write a long (4 bytes)
|
* WriteLong(data) : Write a long (4 bytes)
|
||||||
StartRead(page) : Start a read on (page)
|
* StartRead(page) : Start a read on (page)
|
||||||
GetWritePage() : Returns the last page written to
|
* GetWritePage() : Returns the last page written to
|
||||||
GetPage() : Returns the last page read
|
* GetPage() : Returns the last page read
|
||||||
ReadByte()
|
* ReadByte()
|
||||||
ReadInt()
|
* ReadInt()
|
||||||
ReadLong()
|
* ReadLong()
|
||||||
|
*
|
||||||
Properties:
|
* Properties:
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
extern "C" {
|
extern "C" {
|
||||||
// AVR LibC Includes
|
// AVR LibC Includes
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
}
|
}
|
||||||
//#include <FastSerial.h>
|
//#include <FastSerial.h>
|
||||||
//#include <AP_Common.h>
|
//#include <AP_Common.h>
|
||||||
|
@ -48,14 +48,14 @@ extern "C" {
|
||||||
|
|
||||||
#include "DataFlash_APM2.h"
|
#include "DataFlash_APM2.h"
|
||||||
/*
|
/*
|
||||||
#define ENABLE_FASTSERIAL_DEBUG
|
* #define ENABLE_FASTSERIAL_DEBUG
|
||||||
|
*
|
||||||
#ifdef 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)
|
# define serialDebug(fmt, args...) if (FastSerial::getInitialized(0)) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__ , ##args); delay(0); } while(0)
|
||||||
#else
|
##else
|
||||||
# define serialDebug(fmt, args...)
|
# define serialDebug(fmt, args...)
|
||||||
#endif
|
##endif
|
||||||
//*/
|
# //*/
|
||||||
|
|
||||||
// DataFlash is connected to Serial Port 3 (we will use SPI mode)
|
// DataFlash is connected to Serial Port 3 (we will use SPI mode)
|
||||||
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
|
@ -94,11 +94,11 @@ extern "C" {
|
||||||
unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
||||||
{
|
{
|
||||||
/* Wait for empty transmit buffer */
|
/* Wait for empty transmit buffer */
|
||||||
while ( !( UCSR3A & (1<<UDRE3)) );
|
while ( !( UCSR3A & (1<<UDRE3)) ) ;
|
||||||
/* Put data into buffer, sends the data */
|
/* Put data into buffer, sends the data */
|
||||||
UDR3 = data;
|
UDR3 = data;
|
||||||
/* Wait for data to be received */
|
/* Wait for data to be received */
|
||||||
while ( !(UCSR3A & (1<<RXC3)) );
|
while ( !(UCSR3A & (1<<RXC3)) ) ;
|
||||||
/* Get and return received data from buffer */
|
/* Get and return received data from buffer */
|
||||||
return UDR3;
|
return UDR3;
|
||||||
}
|
}
|
||||||
|
@ -231,7 +231,7 @@ uint16_t DataFlash_APM2::PageSize()
|
||||||
// Wait until DataFlash is in ready state...
|
// Wait until DataFlash is in ready state...
|
||||||
void DataFlash_APM2::WaitReady()
|
void DataFlash_APM2::WaitReady()
|
||||||
{
|
{
|
||||||
while(!ReadStatus());
|
while(!ReadStatus()) ;
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||||
|
@ -244,7 +244,7 @@ void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||||
else
|
else
|
||||||
SPI_transfer(DF_TRANSFER_PAGE_TO_BUFFER_2);
|
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 >> 7));
|
||||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||||
}else{
|
}else{
|
||||||
|
@ -257,7 +257,7 @@ void DataFlash_APM2::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
CS_active();
|
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
|
||||||
|
|
||||||
// release SPI bus for use by other sensors
|
// release SPI bus for use by other sensors
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
|
@ -273,7 +273,7 @@ void DataFlash_APM2::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
|
||||||
else
|
else
|
||||||
SPI_transfer(DF_BUFFER_2_TO_PAGE_WITH_ERASE);
|
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 >> 7));
|
||||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||||
}else{
|
}else{
|
||||||
|
@ -288,7 +288,7 @@ void DataFlash_APM2::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, un
|
||||||
|
|
||||||
// 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
|
||||||
|
|
||||||
// release SPI bus for use by other sensors
|
// release SPI bus for use by other sensors
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
|
@ -346,7 +346,7 @@ void DataFlash_APM2::PageErase (uint16_t PageAdr)
|
||||||
// Send page erase command
|
// Send page erase command
|
||||||
SPI_transfer(DF_PAGE_ERASE);
|
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));
|
||||||
SPI_transfer((unsigned char)(PageAdr << 1));
|
SPI_transfer((unsigned char)(PageAdr << 1));
|
||||||
}else{
|
}else{
|
||||||
|
@ -359,7 +359,7 @@ void DataFlash_APM2::PageErase (uint16_t PageAdr)
|
||||||
//initiate flash page erase
|
//initiate flash page erase
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
CS_active();
|
CS_active();
|
||||||
while(!ReadStatus());
|
while(!ReadStatus()) ;
|
||||||
|
|
||||||
// release SPI bus for use by other sensors
|
// release SPI bus for use by other sensors
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
|
@ -387,7 +387,7 @@ void DataFlash_APM2::BlockErase(uint16_t BlockAdr)
|
||||||
//initiate flash page erase
|
//initiate flash page erase
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
CS_active();
|
CS_active();
|
||||||
while(!ReadStatus());
|
while(!ReadStatus()) ;
|
||||||
|
|
||||||
// release SPI bus for use by other sensors
|
// release SPI bus for use by other sensors
|
||||||
CS_inactive();
|
CS_inactive();
|
||||||
|
|
Loading…
Reference in New Issue