|
|
|
@ -339,6 +339,7 @@ struct PACKED log_Performance {
@@ -339,6 +339,7 @@ struct PACKED log_Performance {
|
|
|
|
|
int16_t pm_test; |
|
|
|
|
uint8_t i2c_lockup_count; |
|
|
|
|
uint16_t ins_error_count; |
|
|
|
|
uint32_t log_dropped; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// Write a performance monitoring packet
|
|
|
|
@ -352,9 +353,10 @@ void Copter::Log_Write_Performance()
@@ -352,9 +353,10 @@ void Copter::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(), |
|
|
|
|
log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(), |
|
|
|
|
}; |
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt)); |
|
|
|
|
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Write an attitude packet
|
|
|
|
@ -731,7 +733,7 @@ const struct LogStructure Copter::log_structure[] = {
@@ -731,7 +733,7 @@ const struct LogStructure Copter::log_structure[] = {
|
|
|
|
|
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), |
|
|
|
|
"CTUN", "Qfffffecchh", "TimeUS,ThrIn,AngBst,ThrOut,DAlt,Alt,BarAlt,DSAlt,SAlt,DCRt,CRt" }, |
|
|
|
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
|
|
|
|
"PM", "QHHIhBH", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr" }, |
|
|
|
|
"PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" }, |
|
|
|
|
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt), |
|
|
|
|
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" }, |
|
|
|
|
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
|
|
|
|