mirror of https://github.com/ArduPilot/ardupilot
72 lines
2.3 KiB
C++
72 lines
2.3 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/* ************************************************************ */
|
|
/* Test for DataFlash Log library */
|
|
/* ************************************************************ */
|
|
#ifndef DataFlash_h
|
|
#define DataFlash_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_Class
|
|
{
|
|
public:
|
|
// initialisation
|
|
virtual void Init(void) = 0;
|
|
virtual bool CardInserted(void) = 0;
|
|
|
|
// erase handling
|
|
virtual bool NeedErase(void) = 0;
|
|
virtual void EraseAll() = 0;
|
|
|
|
/* Write a block of data at current offset */
|
|
virtual void WriteBlock(const void *pBuffer, uint16_t size) = 0;
|
|
|
|
/*
|
|
read a packet. The header byte have already been read.
|
|
*/
|
|
virtual void ReadPacket(void *pkt, uint16_t size) = 0;
|
|
|
|
// high level interface
|
|
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 uint16_t start_new_log(void) = 0;
|
|
virtual uint16_t log_read_process(uint8_t log_num,
|
|
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
|
|
*/
|
|
struct log_Header {
|
|
uint8_t head1, head2, msgid;
|
|
};
|
|
};
|
|
|
|
/*
|
|
unfortunately these need to be macros because of a limitation of
|
|
named member structure initialisation in g++
|
|
*/
|
|
#define LOG_PACKET_HEADER uint8_t head1, head2, msgid;
|
|
#define LOG_PACKET_HEADER_INIT(id) head1 : HEAD_BYTE1, head2 : HEAD_BYTE2, msgid : id
|
|
|
|
// once the logging code is all converted we will remove these from
|
|
// this header
|
|
#define HEAD_BYTE1 0xA3 // Decimal 163
|
|
#define HEAD_BYTE2 0x95 // Decimal 149
|
|
|
|
#include "DataFlash_Block.h"
|
|
#include "DataFlash_File.h"
|
|
|
|
#endif
|