Copter: log INS errors in PM message
This commit is contained in:
parent
7046f44443
commit
1359a8fea5
@ -427,12 +427,12 @@ struct PACKED log_Performance {
|
||||
LOG_PACKET_HEADER;
|
||||
uint8_t renorm_count;
|
||||
uint8_t renorm_blowup;
|
||||
uint8_t gps_fix_count;
|
||||
uint16_t num_long_running;
|
||||
uint16_t num_loops;
|
||||
uint32_t max_time;
|
||||
int16_t pm_test;
|
||||
uint8_t i2c_lockup_count;
|
||||
uint16_t ins_error_count;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet
|
||||
@ -442,12 +442,12 @@ static void Log_Write_Performance()
|
||||
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
|
||||
renorm_count : ahrs.renorm_range_count,
|
||||
renorm_blowup : ahrs.renorm_blowup_count,
|
||||
gps_fix_count : gps_fix_count,
|
||||
num_long_running : perf_info_get_num_long_running(),
|
||||
num_loops : perf_info_get_num_loops(),
|
||||
max_time : perf_info_get_max_time(),
|
||||
pm_test : pmTest1,
|
||||
i2c_lockup_count : hal.i2c->lockup_count()
|
||||
i2c_lockup_count : hal.i2c->lockup_count(),
|
||||
ins_error_count : ins.error_count()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -794,7 +794,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", "BBBHHIhB", "RenCnt,RenBlw,FixCnt,NLon,NLoop,MaxT,PMT,I2CErr" },
|
||||
"PM", "BBHHIhBH", "RenCnt,RenBlw,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" },
|
||||
{ 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
Block a user