From fcee82f9b24bfb4d7b80c4f214e321ef5d222ee2 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Tue, 10 May 2016 16:07:56 +1000 Subject: [PATCH] DataFlash: extend ekf fault status reporting coverage --- libraries/DataFlash/LogFile.cpp | 12 +++++++----- libraries/DataFlash/LogStructure.h | 10 +++++----- 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index ab5753f95a..0e40afe379 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -1216,7 +1216,8 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) Vector3f magVar; float tasVar; Vector2f offset; - uint8_t faultStatus, timeoutStatus; + uint16_t faultStatus; + uint8_t timeoutStatus; nav_filter_status solutionStatus; nav_gps_status gpsStatus {}; ahrs.get_NavEKF().getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset); @@ -1236,7 +1237,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) sqrtvarVT : (int16_t)(100*tasVar), offsetNorth : (int8_t)(offset.x), offsetEast : (int8_t)(offset.y), - faults : (uint8_t)(faultStatus), + faults : (uint16_t)(faultStatus), timeouts : (uint8_t)(timeoutStatus), solution : (uint16_t)(solutionStatus.value), gps : (uint16_t)(gpsStatus.value) @@ -1375,7 +1376,8 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) Vector3f magVar; float tasVar = 0; Vector2f offset; - uint8_t faultStatus=0, timeoutStatus=0; + uint16_t faultStatus=0; + uint8_t timeoutStatus=0; nav_filter_status solutionStatus {}; nav_gps_status gpsStatus {}; ahrs.get_NavEKF2().getVariances(0,velVar, posVar, hgtVar, magVar, tasVar, offset); @@ -1398,7 +1400,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) tiltErr : (float)tiltError, offsetNorth : (int8_t)(offset.x), offsetEast : (int8_t)(offset.y), - faults : (uint8_t)(faultStatus), + faults : (uint16_t)(faultStatus), timeouts : (uint8_t)(timeoutStatus), solution : (uint16_t)(solutionStatus.value), gps : (uint16_t)(gpsStatus.value), @@ -1524,7 +1526,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled) tiltErr : (float)tiltError, offsetNorth : (int8_t)(offset.x), offsetEast : (int8_t)(offset.y), - faults : (uint8_t)(faultStatus), + faults : (uint16_t)(faultStatus), timeouts : (uint8_t)(timeoutStatus), solution : (uint16_t)(solutionStatus.value), gps : (uint16_t)(gpsStatus.value), diff --git a/libraries/DataFlash/LogStructure.h b/libraries/DataFlash/LogStructure.h index fdc84c95ee..25f9f78413 100644 --- a/libraries/DataFlash/LogStructure.h +++ b/libraries/DataFlash/LogStructure.h @@ -314,7 +314,7 @@ struct PACKED log_EKF4 { int16_t sqrtvarVT; int8_t offsetNorth; int8_t offsetEast; - uint8_t faults; + uint16_t faults; uint8_t timeouts; uint16_t solution; uint16_t gps; @@ -331,7 +331,7 @@ struct PACKED log_NKF4 { float tiltErr; int8_t offsetNorth; int8_t offsetEast; - uint8_t faults; + uint16_t faults; uint8_t timeouts; uint16_t solution; uint16_t gps; @@ -782,7 +782,7 @@ Format characters in the format string for binary log messages { LOG_EKF3_MSG, sizeof(log_EKF3), \ "EKF3","Qcccccchhhc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IVT" }, \ { LOG_EKF4_MSG, sizeof(log_EKF4), \ - "EKF4","QcccccccbbBBHH","TimeUS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,OFE,FS,TS,SS,GPS" }, \ + "EKF4","QcccccccbbHBHH","TimeUS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,OFE,FS,TS,SS,GPS" }, \ { LOG_EKF5_MSG, sizeof(log_EKF5), \ "EKF5","QBhhhcccCC","TimeUS,normInnov,FIX,FIY,AFI,HAGL,offset,RI,meaRng,errHAGL" }, \ { LOG_NKF1_MSG, sizeof(log_EKF1), \ @@ -792,7 +792,7 @@ Format characters in the format string for binary log messages { LOG_NKF3_MSG, sizeof(log_NKF3), \ "NKF3","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT" }, \ { LOG_NKF4_MSG, sizeof(log_NKF4), \ - "NKF4","QcccccfbbBBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI" }, \ + "NKF4","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI" }, \ { LOG_NKF5_MSG, sizeof(log_EKF5), \ "NKF5","QBhhhcccCC","TimeUS,normInnov,FIX,FIY,AFI,HAGL,offset,RI,meaRng,errHAGL" }, \ { LOG_NKF6_MSG, sizeof(log_EKF1), \ @@ -802,7 +802,7 @@ Format characters in the format string for binary log messages { LOG_NKF8_MSG, sizeof(log_NKF3), \ "NKF8","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT" }, \ { LOG_NKF9_MSG, sizeof(log_NKF4), \ - "NKF9","QcccccfbbBBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI" }, \ + "NKF9","QcccccfbbHBHHb","TimeUS,SV,SP,SH,SM,SVT,errRP,OFN,OFE,FS,TS,SS,GPS,PI" }, \ { LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \ "TERR","QBLLHffHH","TimeUS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded" }, \ { LOG_GPS_UBX1_MSG, sizeof(log_Ubx1), \