ardupilot/Tools/Replay/DataFlashFileReader.h
Peter Barker 5452730fc9 Tools: Replay: make it work again
Tools: Replay: ignore setting of LOG_DISARMED

Otherwise log files that come in with LOG_DISARMED false don't get any
significant output

Tools: Replay: apply user parameters after any PARM message

Tools: Replay: emit timestamp when EKF is force-started

Tools: Replay: use stderr for what it's good for

Tools: Replay: force log disarmed
2018-10-31 16:05:33 +11:00

37 lines
817 B
C++

#pragma once
#include <DataFlash/DataFlash.h>
#define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE
class DataFlashFileReader
{
public:
DataFlashFileReader();
~DataFlashFileReader();
bool open_log(const char *logfile);
bool update(char type[5]);
virtual bool handle_log_format_msg(const struct log_Format &f) = 0;
virtual bool handle_msg(const struct log_Format &f, uint8_t *msg) = 0;
void format_type(uint16_t type, char dest[5]);
void get_packet_counts(uint64_t dest[]);
protected:
int fd = -1;
struct log_Format formats[LOGREADER_MAX_FORMATS] {};
private:
ssize_t read_input(void *buf, size_t count);
uint64_t bytes_read = 0;
uint32_t message_count = 0;
uint64_t start_micros;
uint64_t packet_counts[LOGREADER_MAX_FORMATS] = {};
};