Replay: save CHEK messages when not being generated

This commit is contained in:
Andrew Tridgell 2015-07-09 10:20:45 +10:00
parent 2e6b6e473a
commit f2106f39aa
3 changed files with 23 additions and 3 deletions

View File

@ -28,7 +28,9 @@
extern const AP_HAL::HAL& hal;
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps, AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const struct LogStructure *_structure, uint8_t _num_types, const char **&_nottypes) :
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps,
AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const struct LogStructure *_structure,
uint8_t _num_types, const char **&_nottypes):
vehicle(VehicleType::VEHICLE_UNKNOWN),
ahrs(_ahrs),
ins(_ins),
@ -123,6 +125,15 @@ uint8_t LogReader::map_fmt_type(const char *name, uint8_t intype)
return mapped_msgid[intype];
}
bool LogReader::save_message_type(const char *name)
{
bool save_message = !in_list(name, generated_names);
if (save_chek_messages && strcmp(name, "CHEK") == 0) {
save_message = true;
}
return save_message;
}
bool LogReader::handle_log_format_msg(const struct log_Format &f)
{
char name[5];
@ -130,7 +141,7 @@ bool LogReader::handle_log_format_msg(const struct log_Format &f)
memcpy(name, f.name, 4);
debug("Defining log format for type (%d) (%s)\n", f.type, name);
if (!in_list(name, generated_names)) {
if (save_message_type(name)) {
/*
any messages which we won't be generating internally in
replay should get the original FMT header
@ -249,7 +260,7 @@ bool LogReader::handle_msg(const struct log_Format &f, uint8_t *msg) {
memset(name, '\0', 5);
memcpy(name, f.name, 4);
if (!in_list(name, generated_names)) {
if (save_message_type(name)) {
if (mapped_msgid[msg[2]] == 0) {
printf("Unknown msgid %u\n", (unsigned)msg[2]);
exit(1);

View File

@ -22,6 +22,7 @@ public:
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; }
virtual bool handle_log_format_msg(const struct log_Format &f);
@ -70,7 +71,11 @@ private:
bool installed_vehicle_specific_parsers;
const char **&nottypes;
bool save_chek_messages;
void maybe_install_vehicle_specific_parsers();
uint8_t map_fmt_type(const char *name, uint8_t intype);
bool save_message_type(const char *name);
};

View File

@ -554,6 +554,10 @@ void Replay::setup()
_parse_command_line(argc, argv);
if (!check_generate) {
logreader.set_save_chek_messages(true);
}
// _parse_command_line sets up an FPE handler. We can do better:
signal(SIGFPE, _replay_sig_fpe);