mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Replay: include a minimal set of FMT messages at start of log
This commit is contained in:
parent
366d95f45e
commit
1e44251d35
@ -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" }
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user