mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF3: apply height innovation floor only when barometer is in use
This commit is contained in:
parent
c53125f3b5
commit
c7a73e84d6
@ -608,7 +608,7 @@ void NavEKF3_core::FuseVelPosNED()
|
|||||||
const float gndMaxBaroErr = 4.0f;
|
const float gndMaxBaroErr = 4.0f;
|
||||||
const float gndBaroInnovFloor = -0.5f;
|
const float gndBaroInnovFloor = -0.5f;
|
||||||
|
|
||||||
if(getTouchdownExpected()) {
|
if(getTouchdownExpected() && activeHgtSource == HGT_SOURCE_BARO) {
|
||||||
// when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
|
// when a touchdown is expected, floor the barometer innovation at gndBaroInnovFloor
|
||||||
// constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
|
// constrain the correction between 0 and gndBaroInnovFloor+gndMaxBaroErr
|
||||||
// this function looks like this:
|
// this function looks like this:
|
||||||
|
Loading…
Reference in New Issue
Block a user