mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_NavEKF3: Fix origin height estimator indexing bug
EKF3 should use index 9 to access vertical position states
This commit is contained in:
parent
002494c048
commit
6a1055389d
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user