Sub: add available memory to PM message

This commit is contained in:
Andrew Tridgell 2017-03-27 08:12:11 +11:00 committed by Randy Mackay
parent c76eadf4f6
commit 5d642f98f5

View File

@ -295,6 +295,7 @@ struct PACKED log_Performance {
uint8_t i2c_lockup_count; uint8_t i2c_lockup_count;
uint16_t ins_error_count; uint16_t ins_error_count;
uint32_t log_dropped; uint32_t log_dropped;
uint32_t mem_avail;
}; };
// Write a performance monitoring packet // Write a performance monitoring packet
@ -310,6 +311,7 @@ void Sub::Log_Write_Performance()
i2c_lockup_count : 0, i2c_lockup_count : 0,
ins_error_count : ins.error_count(), ins_error_count : ins.error_count(),
log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(), log_dropped : DataFlash.num_dropped() - perf_info_get_num_dropped(),
hal.util->available_memory()
}; };
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt)); DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
} }
@ -585,7 +587,7 @@ const struct LogStructure Sub::log_structure[] = {
{ LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning), { LOG_CONTROL_TUNING_MSG, sizeof(log_Control_Tuning),
"CTUN", "Qffffffeccfhh", "TimeUS,ThrIn,ABst,ThrOut,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" }, "CTUN", "Qffffffeccfhh", "TimeUS,ThrIn,ABst,ThrOut,DAlt,Alt,BAlt,DSAlt,SAlt,TAlt,DCRt,CRt" },
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), { LOG_PERFORMANCE_MSG, sizeof(log_Performance),
"PM", "QHHIhBHI", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop" }, "PM", "QHHIhBHII", "TimeUS,NLon,NLoop,MaxT,PMT,I2CErr,INSErr,LogDrop,Mem" },
{ LOG_MOTBATT_MSG, sizeof(log_MotBatt), { LOG_MOTBATT_MSG, sizeof(log_MotBatt),
"MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" }, "MOTB", "Qffff", "TimeUS,LiftMax,BatVolt,BatRes,ThLimit" },
{ LOG_EVENT_MSG, sizeof(log_Event), { LOG_EVENT_MSG, sizeof(log_Event),