ardupilot/libraries/DataFlash/DataFlash_File.h

99 lines
2.7 KiB
C
Raw Normal View History

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
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
#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)
#endif
class DataFlash_File : public DataFlash_Class
2013-02-28 16:17:58 -04:00
{
public:
// constructor
DataFlash_File(const char *log_directory);
// initialisation
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);
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
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);
uint16_t get_num_logs(void);
uint16_t start_new_log(void);
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port);
2013-02-28 16:17:58 -04:00
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
void ListAvailableLogs(AP_HAL::BetterStream *port);
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;
uint16_t _read_fd_log_num;
uint32_t _read_offset;
uint32_t _write_offset;
2013-09-28 03:29:58 -03:00
volatile bool _initialised;
volatile bool _open_error;
2013-02-28 16:17:58 -04:00
const char *_log_directory;
/*
read a block
*/
void ReadBlock(void *pkt, uint16_t size);
2013-02-28 16:17:58 -04:00
// write buffer
2013-09-28 03:29:58 -03:00
uint8_t *_writebuf;
uint16_t _writebuf_size;
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. */
char *_log_file_name(uint16_t log_num);
char *_lastlog_file_name(void);
uint32_t _get_log_size(uint16_t log_num);
uint32_t _get_log_time(uint16_t log_num);
void stop_logging(void);
2013-09-28 03:29:58 -03:00
void _io_timer(void);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// performance counters
perf_counter_t _perf_write;
perf_counter_t _perf_fsync;
perf_counter_t _perf_errors;
perf_counter_t _perf_overruns;
#endif
2013-02-28 16:17:58 -04:00
};
#endif // DataFlash_File_h