From 31142c0322dec11b9b831036036e359c229c11ad Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Thu, 19 Apr 2018 08:01:41 +1000 Subject: [PATCH] EKF: tighten wind variance growth check --- EKF/covariance.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/EKF/covariance.cpp b/EKF/covariance.cpp index 4f31fed811..14b4e3cb69 100644 --- a/EKF/covariance.cpp +++ b/EKF/covariance.cpp @@ -210,7 +210,7 @@ void Ekf::predictCovariance() float wind_vel_sig; // Don't continue to grow wind velocity state variances if they are becoming too large or we are not using wind velocity states as this can make the covariance matrix badly conditioned - if (_control_status.flags.wind && (P[22][22] + P[23][23]) < 2.0f * sq(_params.initial_wind_uncertainty)) { + if (_control_status.flags.wind && (P[22][22] + P[23][23]) < sq(_params.initial_wind_uncertainty)) { wind_vel_sig = dt * math::constrain(_params.wind_vel_p_noise, 0.0f, 1.0f); } else {