diff --git a/libraries/AP_NavEKF3/LogStructure.h b/libraries/AP_NavEKF3/LogStructure.h index 0a0ceb9016..702c066682 100644 --- a/libraries/AP_NavEKF3/LogStructure.h +++ b/libraries/AP_NavEKF3/LogStructure.h @@ -173,7 +173,7 @@ struct PACKED log_XKF3 { // @LoggerMessage: XKF4 -// @Description: EKF3 variances +// @Description: EKF3 variances. SV, SP, SH and SM are probably best described as 'Squared Innovation Test Ratios' where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK3_MAG_I_GATE, EK3_HGT_I_GATE, etc // @Field: TimeUS: Time since system startup // @Field: C: EKF3 core this data is for // @Field: SV: Square root of the velocity variance