mirror of https://github.com/ArduPilot/ardupilot
Plane: add available memory to PM message
This commit is contained in:
parent
01206f9e59
commit
c76eadf4f6
|
@ -214,6 +214,7 @@ struct PACKED log_Performance {
|
|||
uint32_t g_dt_max;
|
||||
uint32_t g_dt_min;
|
||||
uint32_t log_dropped;
|
||||
uint32_t mem_avail;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
|
@ -226,7 +227,8 @@ void Plane::Log_Write_Performance()
|
|||
main_loop_count : perf.mainLoop_count,
|
||||
g_dt_max : perf.G_Dt_max,
|
||||
g_dt_min : perf.G_Dt_min,
|
||||
log_dropped : DataFlash.num_dropped() - perf.last_log_dropped
|
||||
log_dropped : DataFlash.num_dropped() - perf.last_log_dropped,
|
||||
hal.util->available_memory()
|
||||
};
|
||||
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
@ -480,7 +482,7 @@ void Plane::Log_Write_Home_And_Origin()
|
|||
const struct LogStructure Plane::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "QHHIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop" },
|
||||
"PM", "QHHIIII", "TimeUS,NLon,NLoop,MaxT,MinT,LogDrop,Mem" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
|
|
Loading…
Reference in New Issue