DataFlash: Update logging of EKF2 primary core index

Changes made in response to review comments
This commit is contained in:
Paul Riseborough 2015-11-06 14:04:53 +11:00 committed by Andrew Tridgell
parent 2dcaeb0304
commit 987d261109
2 changed files with 4 additions and 5 deletions

View File

@ -461,7 +461,7 @@ struct PACKED log_NKF4 {
uint8_t timeouts;
uint16_t solution;
uint16_t gps;
uint8_t primary;
int8_t primary;
};
struct PACKED log_EKF5 {
@ -832,7 +832,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","QcccccfbbBBHHb","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_TERRAIN_MSG, sizeof(log_TERRAIN), \

View File

@ -1367,8 +1367,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
ahrs.get_NavEKF2().getFilterGpsStatus(gpsStatus);
float tiltError;
ahrs.get_NavEKF2().getTiltError(tiltError);
uint8_t primaryIndex;
ahrs.get_NavEKF2().getPrimaryCoreIndex(primaryIndex);
uint8_t primaryIndex = ahrs.get_NavEKF2().getPrimaryCoreIndex();
struct log_NKF4 pkt4 = {
LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG),
time_us : hal.scheduler->micros64(),
@ -1384,7 +1383,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
timeouts : (uint8_t)(timeoutStatus),
solution : (uint16_t)(solutionStatus.value),
gps : (uint16_t)(gpsStatus.value),
primary : (uint8_t)primaryIndex
primary : (int8_t)primaryIndex
};
WriteBlock(&pkt4, sizeof(pkt4));