AP_NavEKF3: Fix terrain estimator innovation consistency check

This commit is contained in:
priseborough 2017-06-20 09:40:25 +10:00 committed by Francisco Ferreira
parent ce8e935896
commit 06d40a7901
1 changed files with 2 additions and 3 deletions

View File

@ -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;