2013-02-23 03:52:30 -04:00
|
|
|
/// -*- 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>
|
|
|
|
|
2013-04-19 04:49:16 -03:00
|
|
|
class DataFlash_Block : public DataFlash_Class
|
2013-02-23 03:52:30 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
// initialisation
|
2013-12-16 20:12:42 -04:00
|
|
|
virtual void Init(const struct LogStructure *structure, uint8_t num_types) = 0;
|
2013-02-23 03:52:30 -04:00
|
|
|
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);
|
|
|
|
|
|
|
|
// high level interface
|
|
|
|
uint16_t find_last_log(void);
|
2013-04-17 08:32:53 -03:00
|
|
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
2013-12-15 03:57:49 -04:00
|
|
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
2013-12-16 20:12:42 -04:00
|
|
|
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
2013-12-15 03:57:49 -04:00
|
|
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
2013-04-17 08:32:53 -03:00
|
|
|
uint16_t get_num_logs(void);
|
2013-03-14 17:30:23 -03:00
|
|
|
uint16_t start_new_log(void);
|
2014-08-01 02:57:15 -03:00
|
|
|
#ifndef DATAFLASH_NO_CLI
|
2013-04-19 04:49:16 -03:00
|
|
|
void LogReadProcess(uint16_t log_num,
|
|
|
|
uint16_t start_page, uint16_t end_page,
|
2013-04-20 02:17:49 -03:00
|
|
|
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
|
2013-04-19 04:49:16 -03:00
|
|
|
AP_HAL::BetterStream *port);
|
2013-02-23 03:52:30 -04:00
|
|
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
|
|
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
2014-08-01 03:13:43 -03:00
|
|
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
2014-08-01 02:57:15 -03:00
|
|
|
#endif
|
2013-02-23 03:52:30 -04:00
|
|
|
|
|
|
|
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;
|
|
|
|
|
2013-12-16 20:14:33 -04:00
|
|
|
// offset from adding FMT messages to log data
|
|
|
|
bool adding_fmt_headers;
|
|
|
|
|
2013-02-23 03:52:30 -04:00
|
|
|
/*
|
|
|
|
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();
|
|
|
|
|
2013-12-16 20:12:42 -04:00
|
|
|
void _print_log_formats(AP_HAL::BetterStream *port);
|
2013-11-08 20:09:42 -04:00
|
|
|
|
2013-02-23 03:52:30 -04:00
|
|
|
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
|
|
|
|
|