ardupilot/Tools/Replay/DataFlashFileReader.h
Peter Barker 1cefd2943b Replay: correct various atrophications in Replay tool
Replay: tear down threads before exitting

NKQ is a generated name - don't copy it across to output

Stop whinging about presence of NKF6 and friends; we know these generated names are not going to be present in modern logs

memcpy rather than strncpy within log_FMT

Correct strings vs optionally-terminated structure entries in sanity checks

Call AP_Param::load_all() to start the parameter saving thread.  AP_Compass' init() method now saves parameters (compass reordering), and because we're disarmed we will block until the parameter is pushed onto the to-save queue; if there's no thread popping off that list we block indefinitely.

Remove duplicate definitions of various singleton objects.

Replay: write out GPS message to output log

Useful for diagnosis, but also because we struggle to find a time base
without this and the pymavlink tools take forever to work

Replay: set COMPASS_DEV_ID and COMPASS_PRIO1_ID so EKF gets mag data

Replay: avoid use of system clock; use stopped-clock only

Replay: constraint to emitting output for single core only
2020-09-15 10:02:36 +10:00

37 lines
847 B
C++

#pragma once
#include <AP_Logger/AP_Logger.h>
#define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE
class AP_LoggerFileReader
{
public:
AP_LoggerFileReader();
~AP_LoggerFileReader();
bool open_log(const char *logfile);
bool update(char type[5], uint8_t &core);
virtual bool handle_log_format_msg(const struct log_Format &f) = 0;
virtual bool handle_msg(const struct log_Format &f, uint8_t *msg, uint8_t &core) = 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] = {};
};