AP_NavEKF2: improve description of XKF4/NKF4 fields
Courtesy Paul Riseborough here: https://github.com/ArduPilot/ardupilot_wiki/issues/3641#issuecomment-913577132
This commit is contained in:
parent
abe78e168d
commit
a62cb64867
@ -166,7 +166,7 @@ struct PACKED log_NKF3 {
|
||||
|
||||
|
||||
// @LoggerMessage: NKF4
|
||||
// @Description: EKF2 variances
|
||||
// @Description: EKF2 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 EK2_MAG_I_GATE, EK2_HGT_I_GATE, etc
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: C: EKF2 core this data is for
|
||||
// @Field: SV: Square root of the velocity variance
|
||||
|
Loading…
Reference in New Issue
Block a user