mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_NavEKF3: Initialise mag field variances to non zero values
This commit is contained in:
parent
0b96f046c2
commit
9168d0cd19
@ -602,11 +602,11 @@ void NavEKF3_core::CovarianceInit()
|
||||
P[14][14] = P[13][13];
|
||||
P[15][15] = P[13][13];
|
||||
// earth magnetic field
|
||||
P[16][16] = 0.0f;
|
||||
P[16][16] = sq(frontend->_magNoise);
|
||||
P[17][17] = P[16][16];
|
||||
P[18][18] = P[16][16];
|
||||
// body magnetic field
|
||||
P[19][19] = 0.0f;
|
||||
P[19][19] = sq(frontend->_magNoise);
|
||||
P[20][20] = P[19][19];
|
||||
P[21][21] = P[19][19];
|
||||
// wind velocities
|
||||
|
Loading…
Reference in New Issue
Block a user