ardupilot/Tools/Replay/LogReader.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

95 lines
2.7 KiB
C++

#include "VehicleType.h"
#include "DataFlashFileReader.h"
#include "LR_MsgHandler.h"
#include "Parameters.h"
class LogReader : public AP_LoggerFileReader
{
public:
LogReader(AP_AHRS &_ahrs,
AP_InertialSensor &_ins,
Compass &_compass,
AP_GPS &_gps,
AP_Airspeed &_airspeed,
AP_Logger &_logger,
struct LogStructure *log_structure,
uint8_t log_structure_count,
const char **&nottypes);
const Vector3f &get_attitude(void) const { return attitude; }
const Vector3f &get_ahr2_attitude(void) const { return ahr2_attitude; }
const Vector3f &get_inavpos(void) const { return inavpos; }
const Vector3f &get_sim_attitude(void) const { return sim_attitude; }
const float &get_relalt(void) const { return rel_altitude; }
const LR_MsgHandler::CheckState &get_check_state(void) const { return check_state; }
VehicleType::vehicle_type vehicle;
bool set_parameter(const char *name, float value);
void set_accel_mask(uint8_t mask) { accel_mask = mask; }
void set_gyro_mask(uint8_t mask) { gyro_mask = mask; }
void set_use_imt(bool _use_imt) { use_imt = _use_imt; }
void set_save_chek_messages(bool _save_chek_messages) { save_chek_messages = _save_chek_messages; }
uint64_t last_timestamp_us(void) const { return last_timestamp_usec; }
bool handle_log_format_msg(const struct log_Format &f) override;
bool handle_msg(const struct log_Format &f, uint8_t *msg, uint8_t &core) override;
static bool in_list(const char *type, const char *list[]);
protected:
private:
AP_AHRS &ahrs;
AP_InertialSensor &ins;
Compass &compass;
AP_GPS &gps;
AP_Airspeed &airspeed;
AP_Logger &logger;
struct LogStructure *_log_structure;
uint8_t _log_structure_count;
uint8_t accel_mask;
uint8_t gyro_mask;
bool use_imt = true;
uint32_t ground_alt_cm;
class LR_MsgHandler *msgparser[LOGREADER_MAX_FORMATS] {};
Vector3f attitude;
Vector3f ahr2_attitude;
Vector3f sim_attitude;
Vector3f inavpos;
float rel_altitude;
uint64_t last_timestamp_usec;
// mapping from original msgid to output msgid
uint8_t mapped_msgid[256] {};
// next available msgid for mapping
uint8_t next_msgid = 1;
LR_MsgHandler::CheckState check_state;
bool installed_vehicle_specific_parsers;
const char **&nottypes;
bool save_chek_messages;
void maybe_install_vehicle_specific_parsers();
void initialise_fmt_map();
uint8_t map_fmt_type(const char *name, uint8_t intype);
bool save_message_type(const char *name);
};
// some vars are difficult to get through the layers
struct globals {
bool no_params;
};
extern struct globals globals;