Replay: use dataflash log format messages to extract message data instead of using structs
dataflash logs have been self-describing since 2013. Replay now uses the descriptions supplied in the dataflash log to understand the format of any particular message. This change should allow fields to be added to messages with no impact on Replay.
This commit is contained in:
parent
60bc986e71
commit
42351edfa6
File diff suppressed because it is too large
Load Diff
@ -52,14 +52,65 @@ private:
|
||||
AP_Airspeed &airspeed;
|
||||
DataFlash_Class &dataflash;
|
||||
|
||||
void update_from_msg_imu(uint8_t imu_offset, class MsgParser *p, uint8_t *data);
|
||||
void update_from_msg_gps(uint8_t imu_offset, class MsgParser *p, uint8_t *data, bool responsible_for_relalt);
|
||||
void update_from_msg_compass(uint8_t gps_offset, class MsgParser *p, uint8_t *msg);
|
||||
void wait_timestamp_from_msg(class MsgParser *p, uint8_t *data);
|
||||
|
||||
uint8_t accel_mask;
|
||||
uint8_t gyro_mask;
|
||||
|
||||
uint32_t ground_alt_cm;
|
||||
|
||||
#define LOGREADER_MAX_FORMATS 100
|
||||
uint8_t num_formats;
|
||||
#define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE
|
||||
struct log_Format formats[LOGREADER_MAX_FORMATS];
|
||||
class MsgParser *msgparser[LOGREADER_MAX_FORMATS];
|
||||
|
||||
void force_add_format(struct log_Format *formats, MsgParser **parsers,
|
||||
uint8_t type, const char *format, const char *labels);
|
||||
|
||||
// support for the old PLANE formats
|
||||
void init_old_parsers_plane();
|
||||
#define LOGREADER_MAX_FORMATS_PLANE 20
|
||||
struct log_Format formats_plane[LOGREADER_MAX_FORMATS_PLANE];
|
||||
class MsgParser *msgparser_plane[LOGREADER_MAX_FORMATS_PLANE];
|
||||
// support for the old ROVER formats
|
||||
void init_old_parsers_rover();
|
||||
#define LOGREADER_MAX_FORMATS_ROVER 20
|
||||
struct log_Format formats_rover[LOGREADER_MAX_FORMATS_ROVER];
|
||||
class MsgParser *msgparser_rover[LOGREADER_MAX_FORMATS_ROVER];
|
||||
// support for the old COPTER formats
|
||||
void init_old_parsers_copter();
|
||||
#define LOGREADER_MAX_FORMATS_COPTER 20
|
||||
struct log_Format formats_copter[LOGREADER_MAX_FORMATS_COPTER];
|
||||
class MsgParser *msgparser_copter[LOGREADER_MAX_FORMATS_COPTER];
|
||||
|
||||
template <typename R>
|
||||
void require_field(class MsgParser *p, uint8_t *msg, const char *label, R &ret);
|
||||
void require_field(class MsgParser *p, uint8_t *data, const char *label, char *buffer, uint8_t bufferlen);
|
||||
|
||||
// convenience wrappers around require_field
|
||||
uint16_t require_field_uint16_t(class MsgParser *p, uint8_t *data, const char *label);
|
||||
int16_t require_field_int16_t(class MsgParser *p, uint8_t *data, const char *label);
|
||||
uint8_t require_field_uint8_t(class MsgParser *p, uint8_t *data, const char *label);
|
||||
int32_t require_field_int32_t(class MsgParser *p, uint8_t *data, const char *label);
|
||||
float require_field_float(class MsgParser *p, uint8_t *data, const char *label);
|
||||
void location_from_msg(class MsgParser *p, uint8_t *data,
|
||||
Location &loc,
|
||||
const char *label_lat,
|
||||
const char *label_long,
|
||||
const char *label_alt);
|
||||
void ground_vel_from_msg(class MsgParser *p, uint8_t *data,
|
||||
Vector3f &vel,
|
||||
const char *label_speed,
|
||||
const char *label_course,
|
||||
const char *label_vz);
|
||||
void attitude_from_msg(class MsgParser *p, uint8_t *data,
|
||||
Vector3f &att,
|
||||
const char *label_roll,
|
||||
const char *label_pitch,
|
||||
const char *label_yaw);
|
||||
// end convenience wrappers
|
||||
|
||||
Vector3f attitude;
|
||||
Vector3f ahr2_attitude;
|
||||
@ -70,7 +121,7 @@ private:
|
||||
|
||||
void wait_timestamp(uint32_t timestamp);
|
||||
|
||||
void process_plane(uint8_t type, uint8_t *data, uint16_t length);
|
||||
void process_copter(uint8_t type, uint8_t *data, uint16_t length);
|
||||
void process_rover(uint8_t type, uint8_t *data, uint16_t length);
|
||||
void update_plane(uint8_t type, uint8_t *data, uint16_t length);
|
||||
void update_copter(uint8_t type, uint8_t *data, uint16_t length);
|
||||
void update_rover(uint8_t type, uint8_t *data, uint16_t length);
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user