mirror of https://github.com/ArduPilot/ardupilot
Rover: add available memory to PM message
This commit is contained in:
parent
8387e1e69c
commit
9cbfc4ddd3
|
@ -164,6 +164,7 @@ struct PACKED log_Performance {
|
|||
int16_t gyro_drift_z;
|
||||
uint8_t i2c_lockup_count;
|
||||
uint16_t ins_error_count;
|
||||
uint32_t mem_avail;
|
||||
};
|
||||
|
||||
// Write a performance monitoring packet. Total length : 19 bytes
|
||||
|
@ -179,7 +180,8 @@ void Rover::Log_Write_Performance()
|
|||
gyro_drift_y : (int16_t)(ahrs.get_gyro_drift().y * 1000),
|
||||
gyro_drift_z : (int16_t)(ahrs.get_gyro_drift().z * 1000),
|
||||
i2c_lockup_count: 0,
|
||||
ins_error_count : ins.error_count()
|
||||
ins_error_count : ins.error_count(),
|
||||
hal.util->available_memory()
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
@ -440,7 +442,7 @@ void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_targ
|
|||
const LogStructure Rover::log_structure[] = {
|
||||
LOG_COMMON_STRUCTURES,
|
||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance),
|
||||
"PM", "QIHIhhhBH", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" },
|
||||
"PM", "QIHIhhhBHI", "TimeUS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr,Mem" },
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
|
|
Loading…
Reference in New Issue