AP_NavEKF3: Fix origin height estimator indexing bug

EKF3 should use index 9 to access vertical position states
This commit is contained in:
Paul Riseborough 2018-02-20 17:02:29 +11:00 committed by Randy Mackay
parent 002494c048
commit 6a1055389d

View File

@ -663,7 +663,7 @@ void NavEKF3_core::correctEkfOriginHeight()
// calculate the observation variance assuming EKF error relative to datum is independent of GPS observation error
// when not using GPS as height source
float originHgtObsVar = sq(gpsHgtAccuracy) + P[8][8];
float originHgtObsVar = sq(gpsHgtAccuracy) + P[9][9];
// calculate the correction gain
float gain = ekfOriginHgtVar / (ekfOriginHgtVar + originHgtObsVar);