mirror of https://github.com/ArduPilot/ardupilot
DataFlash : Remove unused numerical divergence metric
This commit is contained in:
parent
210f4397da
commit
aca78d321f
|
@ -338,7 +338,6 @@ struct PACKED log_EKF4 {
|
|||
int8_t offsetNorth;
|
||||
int8_t offsetEast;
|
||||
uint8_t faults;
|
||||
uint8_t divergeRate;
|
||||
};
|
||||
|
||||
struct PACKED log_Cmd {
|
||||
|
@ -466,7 +465,7 @@ struct PACKED log_Ubx2 {
|
|||
{ 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","IcccccccbbBB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS,DS" }, \
|
||||
"EKF4","IcccccccbbB","TimeMS,SV,SP,SH,SMX,SMY,SMZ,SVT,OFN,EFE,FS" }, \
|
||||
{ LOG_TERRAIN_MSG, sizeof(log_TERRAIN), \
|
||||
"TERR","IBLLHffHH","TimeMS,Status,Lat,Lng,Spacing,TerrH,CHeight,Pending,Loaded" }, \
|
||||
{ LOG_UBX1_MSG, sizeof(log_Ubx1), \
|
||||
|
|
|
@ -971,9 +971,8 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
|
|||
float tasVar;
|
||||
Vector2f offset;
|
||||
uint8_t faultStatus;
|
||||
float deltaGyroBias;
|
||||
ahrs.get_NavEKF().getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
|
||||
ahrs.get_NavEKF().getFilterFaults(faultStatus, deltaGyroBias);
|
||||
ahrs.get_NavEKF().getFilterFaults(faultStatus);
|
||||
struct log_EKF4 pkt4 = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_EKF4_MSG),
|
||||
time_ms : hal.scheduler->millis(),
|
||||
|
@ -986,8 +985,7 @@ void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
|
|||
sqrtvarVT : (int16_t)(100*tasVar),
|
||||
offsetNorth : (int8_t)(offset.x),
|
||||
offsetEast : (int8_t)(offset.y),
|
||||
faults : (uint8_t)(faultStatus),
|
||||
divergeRate : (uint8_t)(100*deltaGyroBias)
|
||||
faults : (uint8_t)(faultStatus)
|
||||
};
|
||||
WriteBlock(&pkt4, sizeof(pkt4));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue