AP_NavEKF3: apply height innovation floor only when barometer is in use

This commit is contained in:
Jonathan Challinger 2017-03-24 10:35:16 -07:00 committed by Tom Pittenger
parent c53125f3b5
commit c7a73e84d6
1 changed files with 1 additions and 1 deletions

View File

@ -608,7 +608,7 @@ void NavEKF3_core::FuseVelPosNED()
const float gndMaxBaroErr = 4.0f;
const float gndBaroInnovFloor = -0.5f;
if(getTouchdownExpected()) {
if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) {
// when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
// constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
// this function looks like this: