Browse Source

DataFlash: added Block layer in classes

this will allow the addition of a DataFlash_File implementation of the
DataFlash API which will store logs in a traditional filesystem. That
will align better with the PX4 design, and be more useful for fast
transfer of logs to a host computer
master
Andrew Tridgell 12 years ago
parent
commit
c52ef80f06
  1. 95
      libraries/DataFlash/DataFlash.h
  2. 5
      libraries/DataFlash/DataFlash_APM1.h
  3. 5
      libraries/DataFlash/DataFlash_APM2.h
  4. 26
      libraries/DataFlash/DataFlash_Block.cpp
  5. 122
      libraries/DataFlash/DataFlash_Block.h
  6. 7
      libraries/DataFlash/DataFlash_Empty.h
  7. 2
      libraries/DataFlash/DataFlash_SITL.h
  8. 21
      libraries/DataFlash/LogFile.cpp
  9. 14
      libraries/DataFlash/keywords.txt

95
libraries/DataFlash/DataFlash.h

@ -23,26 +23,26 @@ public: @@ -23,26 +23,26 @@ public:
virtual bool CardInserted(void) = 0;
// erase handling
bool NeedErase(void);
void EraseAll();
virtual bool NeedErase(void) = 0;
virtual void EraseAll() = 0;
/* Write a block of data at current offset */
void WriteBlock(const void *pBuffer, uint16_t size);
virtual void WriteBlock(const void *pBuffer, uint16_t size) = 0;
/*
read a packet, stripping off the header bytes
*/
void ReadPacket(void *pkt, uint16_t size);
virtual void ReadPacket(void *pkt, uint16_t size) = 0;
// high level interface
uint16_t find_last_log(void);
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
uint8_t get_num_logs(void);
void start_new_log(void);
uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
void (*callback)(uint8_t msgid));
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
virtual uint16_t find_last_log(void) = 0;
virtual void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
virtual uint8_t get_num_logs(void) = 0;
virtual void start_new_log(void) = 0;
virtual uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
void (*callback)(uint8_t msgid)) = 0;
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
/*
every logged packet starts with 3 bytes
@ -50,71 +50,6 @@ public: @@ -50,71 +50,6 @@ public:
struct log_Header {
uint8_t head1, head2, msgid;
};
private:
struct PageHeader {
uint16_t FileNumber;
uint16_t FilePage;
};
// DataFlash Log variables...
uint8_t df_BufferNum;
uint8_t df_Read_BufferNum;
uint16_t df_BufferIdx;
uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr;
uint16_t df_Read_PageAdr;
uint16_t df_FileNumber;
uint16_t df_FilePage;
virtual void WaitReady() = 0;
virtual void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait) = 0;
virtual void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr) = 0;
virtual void PageErase(uint16_t PageAdr) = 0;
virtual void BlockErase(uint16_t BlockAdr) = 0;
virtual void ChipErase() = 0;
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size) = 0;
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) = 0;
// start reading at the given page
void StartRead(uint16_t PageAdr);
// internal high level functions
uint16_t find_last_page(void);
uint16_t find_last_page_of_log(uint16_t log_number);
bool check_wrapped(void);
uint16_t GetPage(void);
uint16_t GetWritePage(void);
void StartWrite(uint16_t PageAdr);
void FinishWrite(void);
// Read methods
void ReadBlock(void *pBuffer, uint16_t size);
// file numbers
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFilePage();
uint16_t GetFileNumber();
protected:
uint8_t df_manufacturer;
uint16_t df_device;
// page handling
uint16_t df_PageSize;
uint16_t df_NumPages;
virtual void ReadManufacturerID() = 0;
};
/*
@ -129,10 +64,6 @@ protected: @@ -129,10 +64,6 @@ protected:
#define HEAD_BYTE1 0xA3 // Decimal 163
#define HEAD_BYTE2 0x95 // Decimal 149
#include "DataFlash_APM1.h"
#include "DataFlash_APM2.h"
#include "DataFlash_SITL.h"
#include "DataFlash_Empty.h"
#include "DataFlash_Block.h"
#endif

5
libraries/DataFlash/DataFlash_APM1.h

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#include <AP_HAL.h>
#include "DataFlash.h"
class DataFlash_APM1 : public DataFlash_Class
class DataFlash_APM1 : public DataFlash_Block
{
private:
//Methods
@ -39,9 +39,8 @@ private: @@ -39,9 +39,8 @@ private:
AP_HAL::SPIDeviceDriver *_spi;
AP_HAL::Semaphore *_spi_sem;
public:
DataFlash_APM1() {}
public:
void Init();
void ReadManufacturerID();
bool CardInserted();

5
libraries/DataFlash/DataFlash_APM2.h

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#include <AP_HAL.h>
#include "DataFlash.h"
class DataFlash_APM2 : public DataFlash_Class
class DataFlash_APM2 : public DataFlash_Block
{
private:
//Methods
@ -40,9 +40,8 @@ private: @@ -40,9 +40,8 @@ private:
AP_HAL::SPIDeviceDriver* _spi;
AP_HAL::Semaphore* _spi_sem;
public:
DataFlash_APM2() {}
public:
void Init();
void ReadManufacturerID();
bool CardInserted();

26
libraries/DataFlash/DataFlash.cpp → libraries/DataFlash/DataFlash_Block.cpp

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
extern AP_HAL::HAL& hal;
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Class::StartWrite(uint16_t PageAdr)
void DataFlash_Block::StartWrite(uint16_t PageAdr)
{
df_BufferIdx = 0;
df_BufferNum = 0;
@ -17,7 +17,7 @@ void DataFlash_Class::StartWrite(uint16_t PageAdr) @@ -17,7 +17,7 @@ void DataFlash_Class::StartWrite(uint16_t PageAdr)
WaitReady();
}
void DataFlash_Class::FinishWrite(void)
void DataFlash_Block::FinishWrite(void)
{
// Write Buffer to flash, NO WAIT
BufferToPage(df_BufferNum, df_PageAdr, 0);
@ -31,7 +31,7 @@ void DataFlash_Class::FinishWrite(void) @@ -31,7 +31,7 @@ void DataFlash_Class::FinishWrite(void)
df_BufferIdx = 0;
}
void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size)
void DataFlash_Block::WriteBlock(const void *pBuffer, uint16_t size)
{
while (size > 0) {
uint16_t n = df_PageSize - df_BufferIdx;
@ -65,18 +65,18 @@ void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size) @@ -65,18 +65,18 @@ void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size)
// Get the last page written to
uint16_t DataFlash_Class::GetWritePage()
uint16_t DataFlash_Block::GetWritePage()
{
return df_PageAdr;
}
// Get the last page read
uint16_t DataFlash_Class::GetPage()
uint16_t DataFlash_Block::GetPage()
{
return df_Read_PageAdr;
}
void DataFlash_Class::StartRead(uint16_t PageAdr)
void DataFlash_Block::StartRead(uint16_t PageAdr)
{
df_Read_BufferNum = 0;
df_Read_PageAdr = PageAdr;
@ -94,7 +94,7 @@ void DataFlash_Class::StartRead(uint16_t PageAdr) @@ -94,7 +94,7 @@ void DataFlash_Class::StartRead(uint16_t PageAdr)
df_Read_BufferIdx = sizeof(ph);
}
void DataFlash_Class::ReadBlock(void *pBuffer, uint16_t size)
void DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size)
{
while (size > 0) {
uint16_t n = df_PageSize - df_Read_BufferIdx;
@ -128,28 +128,28 @@ void DataFlash_Class::ReadBlock(void *pBuffer, uint16_t size) @@ -128,28 +128,28 @@ void DataFlash_Class::ReadBlock(void *pBuffer, uint16_t size)
}
}
void DataFlash_Class::ReadPacket(void *pkt, uint16_t size)
void DataFlash_Block::ReadPacket(void *pkt, uint16_t size)
{
ReadBlock((void *)(sizeof(struct log_Header)+(uintptr_t)pkt), size - sizeof(struct log_Header));
}
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
void DataFlash_Block::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
uint16_t DataFlash_Block::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
uint16_t DataFlash_Block::GetFilePage()
{
return df_FilePage;
}
void DataFlash_Class::EraseAll()
void DataFlash_Block::EraseAll()
{
for(uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
BlockErase(j);
@ -167,7 +167,7 @@ void DataFlash_Class::EraseAll() @@ -167,7 +167,7 @@ void DataFlash_Class::EraseAll()
/*
* we need to erase if the logging format has changed
*/
bool DataFlash_Class::NeedErase(void)
bool DataFlash_Block::NeedErase(void)
{
uint32_t version;
StartRead(df_NumPages+1);

122
libraries/DataFlash/DataFlash_Block.h

@ -0,0 +1,122 @@ @@ -0,0 +1,122 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
DataFlash logging - block oriented variant
*/
#ifndef DataFlash_block_h
#define DataFlash_block_h
#include <stdint.h>
// the last page holds the log format in first 4 bytes. Please change
// this if (and only if!) the low level format changes
#define DF_LOGGING_FORMAT 0x28122013
// we use an invalie logging format to test the chip erase
#define DF_LOGGING_FORMAT_INVALID 0x28122012
class DataFlash_Block : DataFlash_Class
{
public:
// initialisation
virtual void Init(void) = 0;
virtual bool CardInserted(void) = 0;
// erase handling
bool NeedErase(void);
void EraseAll();
/* Write a block of data at current offset */
void WriteBlock(const void *pBuffer, uint16_t size);
/*
read a packet, stripping off the header bytes
*/
void ReadPacket(void *pkt, uint16_t size);
// high level interface
uint16_t find_last_log(void);
void get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page);
uint8_t get_num_logs(void);
void start_new_log(void);
uint16_t log_read_process(uint16_t start_page, uint16_t end_page,
void (*callback)(uint8_t msgid));
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
private:
struct PageHeader {
uint16_t FileNumber;
uint16_t FilePage;
};
// DataFlash Log variables...
uint8_t df_BufferNum;
uint8_t df_Read_BufferNum;
uint16_t df_BufferIdx;
uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr;
uint16_t df_Read_PageAdr;
uint16_t df_FileNumber;
uint16_t df_FilePage;
/*
functions implemented by the board specific backends
*/
virtual void WaitReady() = 0;
virtual void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait) = 0;
virtual void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr) = 0;
virtual void PageErase(uint16_t PageAdr) = 0;
virtual void BlockErase(uint16_t BlockAdr) = 0;
virtual void ChipErase() = 0;
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size) = 0;
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) = 0;
// internal high level functions
void StartRead(uint16_t PageAdr);
uint16_t find_last_page(void);
uint16_t find_last_page_of_log(uint16_t log_number);
bool check_wrapped(void);
uint16_t GetPage(void);
uint16_t GetWritePage(void);
void StartWrite(uint16_t PageAdr);
void FinishWrite(void);
// Read methods
void ReadBlock(void *pBuffer, uint16_t size);
// file numbers
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFilePage();
uint16_t GetFileNumber();
protected:
uint8_t df_manufacturer;
uint16_t df_device;
// page handling
uint16_t df_PageSize;
uint16_t df_NumPages;
virtual void ReadManufacturerID() = 0;
};
#include "DataFlash_APM1.h"
#include "DataFlash_APM2.h"
#include "DataFlash_SITL.h"
#include "DataFlash_Empty.h"
#endif // DataFlash_block_h

7
libraries/DataFlash/DataFlash_Empty.h

@ -1,3 +1,5 @@ @@ -1,3 +1,5 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/* ************************************************************ */
/* DataFlash_EMPTY Log library */
/* ************************************************************ */
@ -7,7 +9,7 @@ @@ -7,7 +9,7 @@
#include <AP_HAL.h>
#include "DataFlash.h"
class DataFlash_Empty : public DataFlash_Class
class DataFlash_Empty : public DataFlash_Block
{
private:
//Methods
@ -27,9 +29,8 @@ private: @@ -27,9 +29,8 @@ private:
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size);
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
public:
DataFlash_Empty() {}
public:
void Init();
void ReadManufacturerID();
bool CardInserted();

2
libraries/DataFlash/DataFlash_SITL.h

@ -9,7 +9,7 @@ @@ -9,7 +9,7 @@
#include <AP_HAL.h>
#include "DataFlash.h"
class DataFlash_SITL : public DataFlash_Class
class DataFlash_SITL : public DataFlash_Block
{
private:
//Methods

21
libraries/DataFlash/LogFile.cpp

@ -5,7 +5,7 @@ @@ -5,7 +5,7 @@
// This function determines the number of whole or partial log files in the DataFlash
// Wholly overwritten files are (of course) lost.
uint8_t DataFlash_Class::get_num_logs(void)
uint8_t DataFlash_Block::get_num_logs(void)
{
uint16_t lastpage;
uint16_t last;
@ -40,7 +40,7 @@ uint8_t DataFlash_Class::get_num_logs(void) @@ -40,7 +40,7 @@ uint8_t DataFlash_Class::get_num_logs(void)
// This function starts a new log file in the DataFlash
void DataFlash_Class::start_new_log(void)
void DataFlash_Block::start_new_log(void)
{
uint16_t last_page = find_last_page();
@ -71,7 +71,7 @@ void DataFlash_Class::start_new_log(void) @@ -71,7 +71,7 @@ void DataFlash_Class::start_new_log(void)
// This function finds the first and last pages of a log file
// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
void DataFlash_Class::get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page)
void DataFlash_Block::get_log_boundaries(uint8_t log_num, uint16_t & start_page, uint16_t & end_page)
{
uint16_t num = get_num_logs();
uint16_t look;
@ -117,7 +117,7 @@ void DataFlash_Class::get_log_boundaries(uint8_t log_num, uint16_t & start_page, @@ -117,7 +117,7 @@ void DataFlash_Class::get_log_boundaries(uint8_t log_num, uint16_t & start_page,
}
}
bool DataFlash_Class::check_wrapped(void)
bool DataFlash_Block::check_wrapped(void)
{
StartRead(df_NumPages);
if(GetFileNumber() == 0xFFFF)
@ -128,7 +128,7 @@ bool DataFlash_Class::check_wrapped(void) @@ -128,7 +128,7 @@ bool DataFlash_Class::check_wrapped(void)
// This funciton finds the last log number
uint16_t DataFlash_Class::find_last_log(void)
uint16_t DataFlash_Block::find_last_log(void)
{
uint16_t last_page = find_last_page();
StartRead(last_page);
@ -136,7 +136,7 @@ uint16_t DataFlash_Class::find_last_log(void) @@ -136,7 +136,7 @@ uint16_t DataFlash_Class::find_last_log(void)
}
// This function finds the last page of the last file
uint16_t DataFlash_Class::find_last_page(void)
uint16_t DataFlash_Block::find_last_page(void)
{
uint16_t look;
uint16_t bottom = 1;
@ -177,7 +177,7 @@ uint16_t DataFlash_Class::find_last_page(void) @@ -177,7 +177,7 @@ uint16_t DataFlash_Class::find_last_page(void)
}
// This function finds the last page of a particular log file
uint16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number)
uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
{
uint16_t look;
uint16_t bottom;
@ -235,7 +235,7 @@ uint16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number) @@ -235,7 +235,7 @@ uint16_t DataFlash_Class::find_last_page_of_log(uint16_t log_number)
Call the callback() function on each log message found in the page
range. Return the number of log messages found
*/
uint16_t DataFlash_Class::log_read_process(uint16_t start_page, uint16_t end_page,
uint16_t DataFlash_Block::log_read_process(uint16_t start_page, uint16_t end_page,
void (*callback)(uint8_t msgid))
{
uint8_t log_step = 0;
@ -285,7 +285,7 @@ uint16_t DataFlash_Class::log_read_process(uint16_t start_page, uint16_t end_pag @@ -285,7 +285,7 @@ uint16_t DataFlash_Class::log_read_process(uint16_t start_page, uint16_t end_pag
/*
dump header information from all log pages
*/
void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port)
void DataFlash_Block::DumpPageInfo(AP_HAL::BetterStream *port)
{
for (uint16_t count=1; count<=df_NumPages; count++) {
StartRead(count);
@ -298,7 +298,7 @@ void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port) @@ -298,7 +298,7 @@ void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port)
/*
show information about the device
*/
void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port)
void DataFlash_Block::ShowDeviceInfo(AP_HAL::BetterStream *port)
{
if (!CardInserted()) {
port->println_P(PSTR("No dataflash inserted"));
@ -312,4 +312,3 @@ void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port) @@ -312,4 +312,3 @@ void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port)
(unsigned)df_NumPages+1,
(unsigned)df_PageSize);
}

14
libraries/DataFlash/keywords.txt

@ -1,14 +0,0 @@ @@ -1,14 +0,0 @@
DataFlash KEYWORD1
Init KEYWORD2
ReadManufacturerID KEYWORD2
GetPage KEYWORD2
PageErase KEYWORD2
StartWrite KEYWORD2
StartRead KEYWORD2
ReadByte KEYWORD2
ReadInt KEYWORD2
ReadLong KEYWORD2
WriteByte KEYWORD2
WriteInt KEYWORD2
WriteLong KEYWORD2
Loading…
Cancel
Save