AP_NavEKF2: fixed init of earth state mag variances

we were starting with zero variance for X and Y earth states, it
should start with sq(magNoise)
This commit is contained in:
Andrew Tridgell 2020-09-17 07:54:34 +10:00
parent d6dcbda0d3
commit 534e63e2fa

View File

@ -117,7 +117,7 @@ void NavEKF2_core::setWindMagStateLearningMode()
P[21][21] = bodyMagFieldVar.z;
} else {
// set the variances equal to the observation variances
for (uint8_t index=18; index<=21; index++) {
for (uint8_t index=16; index<=21; index++) {
P[index][index] = sq(frontend->_magNoise);
}