2013-02-28 16:17:58 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
/*
|
|
|
|
DataFlash logging - file oriented variant
|
|
|
|
|
|
|
|
This uses posix file IO to create log files called logNN.dat in the
|
|
|
|
given directory
|
|
|
|
*/
|
|
|
|
|
|
|
|
#ifndef DataFlash_File_h
|
|
|
|
#define DataFlash_File_h
|
|
|
|
|
2014-03-31 14:50:58 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
2014-01-12 23:25:16 -04:00
|
|
|
#include <systemlib/perf_counter.h>
|
|
|
|
#else
|
|
|
|
#define perf_begin(x)
|
|
|
|
#define perf_end(x)
|
2014-01-13 23:28:56 -04:00
|
|
|
#define perf_count(x)
|
2014-01-12 23:25:16 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2015-06-25 10:53:20 -03:00
|
|
|
#include "DataFlash_Backend.h"
|
|
|
|
|
|
|
|
class DataFlash_File : public DataFlash_Backend
|
2013-02-28 16:17:58 -04:00
|
|
|
{
|
|
|
|
public:
|
|
|
|
// constructor
|
2015-06-25 10:53:20 -03:00
|
|
|
DataFlash_File(DataFlash_Class &front, const char *log_directory);
|
2013-02-28 16:17:58 -04:00
|
|
|
|
|
|
|
// initialisation
|
2013-12-16 20:12:42 -04:00
|
|
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
2013-02-28 16:17:58 -04:00
|
|
|
bool CardInserted(void);
|
|
|
|
|
|
|
|
// 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);
|
|
|
|
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);
|
2015-07-01 07:22:53 -03:00
|
|
|
bool _log_exists(uint16_t log_num);
|
2013-03-14 17:30:23 -03:00
|
|
|
uint16_t start_new_log(void);
|
2013-04-19 04:49:16 -03:00
|
|
|
void LogReadProcess(uint16_t log_num,
|
|
|
|
uint16_t start_page, uint16_t end_page,
|
2015-05-12 03:59:55 -03:00
|
|
|
print_mode_fn print_mode,
|
2013-04-19 04:49:16 -03:00
|
|
|
AP_HAL::BetterStream *port);
|
2013-02-28 16:17:58 -04:00
|
|
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
|
|
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
2013-04-17 08:32:53 -03:00
|
|
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
2013-02-28 16:17:58 -04:00
|
|
|
|
2015-06-18 22:57:01 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
|
|
void flush(void);
|
|
|
|
#endif
|
|
|
|
|
2013-02-28 16:17:58 -04:00
|
|
|
private:
|
2013-09-28 03:29:58 -03:00
|
|
|
int _write_fd;
|
2013-02-28 16:17:58 -04:00
|
|
|
int _read_fd;
|
2013-12-15 03:57:49 -04:00
|
|
|
uint16_t _read_fd_log_num;
|
2013-04-17 08:32:53 -03:00
|
|
|
uint32_t _read_offset;
|
2014-01-12 23:25:16 -04:00
|
|
|
uint32_t _write_offset;
|
2013-09-28 03:29:58 -03:00
|
|
|
volatile bool _initialised;
|
2014-12-20 22:31:27 -04:00
|
|
|
volatile bool _open_error;
|
2013-02-28 16:17:58 -04:00
|
|
|
const char *_log_directory;
|
|
|
|
|
2013-04-19 21:25:10 -03:00
|
|
|
/*
|
|
|
|
read a block
|
|
|
|
*/
|
2015-05-30 09:16:22 -03:00
|
|
|
bool ReadBlock(void *pkt, uint16_t size);
|
2013-04-19 21:25:10 -03:00
|
|
|
|
2013-02-28 16:17:58 -04:00
|
|
|
// write buffer
|
2013-09-28 03:29:58 -03:00
|
|
|
uint8_t *_writebuf;
|
2014-09-09 04:32:35 -03:00
|
|
|
uint16_t _writebuf_size;
|
2014-01-12 23:25:16 -04:00
|
|
|
const uint16_t _writebuf_chunk;
|
2013-09-28 03:29:58 -03:00
|
|
|
volatile uint16_t _writebuf_head;
|
|
|
|
volatile uint16_t _writebuf_tail;
|
|
|
|
uint32_t _last_write_time;
|
2013-02-28 16:17:58 -04:00
|
|
|
|
|
|
|
/* construct a file name given a log number. Caller must free. */
|
2013-04-17 08:32:53 -03:00
|
|
|
char *_log_file_name(uint16_t log_num);
|
|
|
|
char *_lastlog_file_name(void);
|
|
|
|
uint32_t _get_log_size(uint16_t log_num);
|
2013-12-15 03:57:49 -04:00
|
|
|
uint32_t _get_log_time(uint16_t log_num);
|
2013-04-17 08:32:53 -03:00
|
|
|
|
2013-12-27 23:24:28 -04:00
|
|
|
void stop_logging(void);
|
|
|
|
|
2013-09-28 03:29:58 -03:00
|
|
|
void _io_timer(void);
|
2014-01-12 23:25:16 -04:00
|
|
|
|
2014-03-31 14:50:58 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
2014-01-12 23:25:16 -04:00
|
|
|
// performance counters
|
|
|
|
perf_counter_t _perf_write;
|
|
|
|
perf_counter_t _perf_fsync;
|
|
|
|
perf_counter_t _perf_errors;
|
2015-04-21 07:42:08 -03:00
|
|
|
perf_counter_t _perf_overruns;
|
2014-01-12 23:25:16 -04:00
|
|
|
#endif
|
2013-02-28 16:17:58 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
#endif // DataFlash_File_h
|
|
|
|
|