forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 2
/
LogReader.h
94 lines (71 loc) · 2.73 KB
/
LogReader.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
#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 **¬types);
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 **¬types;
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;