mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 09:53:58 -04:00
AP_NavEKF2: Fix terrain estimator innovation consistency check
This commit is contained in:
parent
647fb51688
commit
fc36bd7874
@ -145,9 +145,8 @@ void NavEKF2_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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user