Browse Source
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 computermaster
9 changed files with 183 additions and 146 deletions
@ -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
|
||||||
|
|
@ -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…
Reference in new issue