mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AP_NavEKF3: 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:
parent
534e63e2fa
commit
1f21d72c79
@ -121,7 +121,7 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
|||||||
P[21][21] = bodyMagFieldVar.z;
|
P[21][21] = bodyMagFieldVar.z;
|
||||||
} else {
|
} else {
|
||||||
// set the variances equal to the observation variances
|
// 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);
|
P[index][index] = sq(frontend->_magNoise);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user