From ac329ec31cdd6e46d645713e5bf8279d8ff9cb73 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Tue, 24 May 2016 11:08:33 +1000 Subject: [PATCH] AP_NavEKF2: use observation noise to set initial magnetic field variances --- libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index e458588288..e10777dfc8 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -1350,11 +1350,11 @@ Quaternion NavEKF2_core::calcQuatAndFieldStates(float roll, float pitch) zeroRows(P,16,21); zeroCols(P,16,21); // set initial earth magnetic field variances - P[16][16] = sq(0.05f); + P[16][16] = sq(frontend->_magNoise); P[17][17] = P[16][16]; P[18][18] = P[16][16]; // set initial body magnetic field variances - P[19][19] = sq(0.05f); + P[19][19] = sq(frontend->_magNoise); P[20][20] = P[19][19]; P[21][21] = P[19][19];