mirror of https://github.com/ArduPilot/ardupilot
Copter: add INAV error count to PM dataflash msg
This commit is contained in:
parent
dacca04b21
commit
965af43121
|
@ -433,6 +433,7 @@ struct PACKED log_Performance {
|
|||
int16_t pm_test;
|
||||
uint8_t i2c_lockup_count;
|
||||
uint16_t ins_error_count;
|
||||
uint8_t inav_error_count;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet
|
||||
|
@ -447,7 +448,8 @@ static void Log_Write_Performance()
|
|||
max_time : perf_info_get_max_time(),
|
||||
pm_test : pmTest1,
|
||||
i2c_lockup_count : hal.i2c->lockup_count(),
|
||||
ins_error_count : ins.error_count()
|
||||
ins_error_count : ins.error_count(),
|
||||
inav_error_count : inertial_nav.error_count()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
@ -794,7 +796,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
|||
{ LOG_COMPASS_MSG, sizeof(log_Compass),
|
||||
"MAG", "hhhhhhhhh", "MagX,MagY,MagZ,OfsX,OfsY,OfsZ,MOfsX,MOfsY,MOfsZ" },
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "BBHHIhBH", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
|
||||
"PM", "BBHHIhBHB", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,INAVErr" },
|
||||
{ LOG_CMD_MSG, sizeof(log_Cmd),
|
||||
"CMD", "BBBBBeLL", "CTot,CNum,CId,COpt,Prm1,Alt,Lat,Lng" },
|
||||
{ LOG_ATTITUDE_MSG, sizeof(log_Attitude),
|
||||
|
|
Loading…
Reference in New Issue