mirror of https://github.com/ArduPilot/ardupilot
DataFlash: Update logging of EKF2 primary core index
Changes made in response to review comments
This commit is contained in:
parent
2dcaeb0304
commit
987d261109
|
@ -461,7 +461,7 @@ struct PACKED log_NKF4 {
|
||||||
uint8_t timeouts;
|
uint8_t timeouts;
|
||||||
uint16_t solution;
|
uint16_t solution;
|
||||||
uint16_t gps;
|
uint16_t gps;
|
||||||
uint8_t primary;
|
int8_t primary;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_EKF5 {
|
struct PACKED log_EKF5 {
|
||||||
|
@ -832,7 +832,7 @@ Format characters in the format string for binary log messages
|
||||||
{ LOG_NKF3_MSG, sizeof(log_NKF3), \
|
{ LOG_NKF3_MSG, sizeof(log_NKF3), \
|
||||||
"NKF3","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT" }, \
|
"NKF3","Qcccccchhhcc","TimeUS,IVN,IVE,IVD,IPN,IPE,IPD,IMX,IMY,IMZ,IYAW,IVT" }, \
|
||||||
{ LOG_NKF4_MSG, sizeof(log_NKF4), \
|
{ 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), \
|
{ LOG_NKF5_MSG, sizeof(log_EKF5), \
|
||||||
"NKF5","QBhhhcccCC","TimeUS,normInnov,FIX,FIY,AFI,HAGL,offset,RI,meaRng,errHAGL" }, \
|
"NKF5","QBhhhcccCC","TimeUS,normInnov,FIX,FIY,AFI,HAGL,offset,RI,meaRng,errHAGL" }, \
|
||||||
{ LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \
|
{ LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \
|
||||||
|
|
|
@ -1367,8 +1367,7 @@ void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs, bool optFlowEnabled)
|
||||||
ahrs.get_NavEKF2().getFilterGpsStatus(gpsStatus);
|
ahrs.get_NavEKF2().getFilterGpsStatus(gpsStatus);
|
||||||
float tiltError;
|
float tiltError;
|
||||||
ahrs.get_NavEKF2().getTiltError(tiltError);
|
ahrs.get_NavEKF2().getTiltError(tiltError);
|
||||||
uint8_t primaryIndex;
|
uint8_t primaryIndex = ahrs.get_NavEKF2().getPrimaryCoreIndex();
|
||||||
ahrs.get_NavEKF2().getPrimaryCoreIndex(primaryIndex);
|
|
||||||
struct log_NKF4 pkt4 = {
|
struct log_NKF4 pkt4 = {
|
||||||
LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG),
|
||||||
time_us : hal.scheduler->micros64(),
|
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),
|
timeouts : (uint8_t)(timeoutStatus),
|
||||||
solution : (uint16_t)(solutionStatus.value),
|
solution : (uint16_t)(solutionStatus.value),
|
||||||
gps : (uint16_t)(gpsStatus.value),
|
gps : (uint16_t)(gpsStatus.value),
|
||||||
primary : (uint8_t)primaryIndex
|
primary : (int8_t)primaryIndex
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt4, sizeof(pkt4));
|
WriteBlock(&pkt4, sizeof(pkt4));
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue