mirror of https://github.com/ArduPilot/ardupilot
DataFlash: EKF logs filter status as uint16
This commit is contained in:
parent
657afcfe7a
commit
3896dadc77
|
@ -506,7 +506,7 @@ struct PACKED log_Esc {
|
|||
{ LOG_EKF3_MSG, sizeof(log_EKF3), \
|
||||
"EKF3","Icccccchhhc","TimeMS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IVT" }, \
|
||||
{ LOG_EKF4_MSG, sizeof(log_EKF4), \
|
||||
"EKF4","IcccccccbbBBB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,TS,SS" }, \
|
||||
"EKF4","IcccccccbbBBH","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,TS,SS" }, \
|
||||
{ LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \
|
||||
"TERR","IBLLHffHH","TimeMS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded" }, \
|
||||
{ LOG_UBX1_MSG, sizeof(log_Ubx1), \
|
||||
|
|
|
@ -1002,7 +1002,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
|||
offsetEast : (int8_t)(offset.y),
|
||||
faults : (uint8_t)(faultStatus),
|
||||
timeouts : (uint8_t)(timeoutStatus),
|
||||
solution : (uint8_t)(solutionStatus.value)
|
||||
solution : (uint16_t)(solutionStatus.value)
|
||||
};
|
||||
WriteBlock(&pkt4, sizeof(pkt4));
|
||||
|
||||
|
|
Loading…
Reference in New Issue