diff --git a/Tools/Replay/LogReader.cpp b/Tools/Replay/LogReader.cpp index 4166938b44..0485e7d670 100644 --- a/Tools/Replay/LogReader.cpp +++ b/Tools/Replay/LogReader.cpp @@ -29,7 +29,7 @@ extern const AP_HAL::HAL& hal; -static const struct LogStructure log_structure[] = { +const struct LogStructure log_structure[] = { LOG_COMMON_STRUCTURES, { LOG_CHEK_MSG, sizeof(log_Chek), "CHEK", "QccCLLffff", "TimeUS,Roll,Pitch,Yaw,Lat,Lng,Alt,VN,VE,VD" } diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index 35fde2024d..f3a604f1a1 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -98,13 +98,22 @@ void ReplayVehicle::load_parameters(void) AP_Param::set_default_by_name("LOG_FILE_BUFSIZE", 60); } +static const struct LogStructure min_log_structure[] = { + { LOG_FORMAT_MSG, sizeof(log_Format), + "FMT", "BBnNZ", "Type,Length,Name,Format,Columns" }, + { LOG_PARAMETER_MSG, sizeof(log_Parameter), + "PARM", "QNf", "TimeUS,Name,Value" }, + { LOG_MESSAGE_MSG, sizeof(log_Message), + "MSG", "QZ", "TimeUS,Message"}, +}; + void ReplayVehicle::setup(void) { load_parameters(); - // we pass zero log structures, as we will be outputting the log - // structures we need manually, to prevent FMT duplicates - dataflash.Init(nullptr, 0); + // we pass a minimal log structure, as we will be outputting the + // log structures we need manually, to prevent FMT duplicates + dataflash.Init(min_log_structure, ARRAY_SIZE(min_log_structure)); dataflash.StartNewLog(); ahrs.set_compass(&compass);