diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp index c7415fcddb..24271a45ec 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_OptFlowFusion.cpp @@ -148,9 +148,8 @@ void NavEKF3_core::EstimateTerrainOffset() // calculate the innovation consistency test ratio auxRngTestRatio = sq(innovRng) / (sq(MAX(0.01f * (float)frontend->_rngInnovGate, 1.0f)) * varInnovRng); - // Check the innovation for consistency and don't fuse if > 5Sigma - if ((sq(innovRng)*SK_RNG) < 25.0f) - { + // Check the innovation test ratio and don't fuse if too large + if (auxRngTestRatio < 1.0f) { // correct the state terrainState -= K_RNG * innovRng;