AP_NavEKF3: Remove unnecessary baro limiting

This commit is contained in:
Paul Riseborough 2021-06-01 10:09:22 +10:00 committed by Randy Mackay
parent 124f016e5b
commit a5a25411da
1 changed files with 0 additions and 5 deletions

View File

@ -1181,11 +1181,6 @@ void NavEKF3_core::selectHeightForFusion()
if (dal.get_takeoff_expected() || dal.get_touchdown_expected()) { if (dal.get_takeoff_expected() || dal.get_touchdown_expected()) {
posDownObsNoise *= frontend->gndEffectBaroScaler; posDownObsNoise *= frontend->gndEffectBaroScaler;
} }
// If we are in takeoff mode, the height measurement is limited to be no less than the measurement at start of takeoff
// This prevents negative baro disturbances due to rotor wash ground interaction corrupting the EKF altitude during initial ascent
if (motorsArmed && dal.get_takeoff_expected() && !assume_zero_sideslip()) {
hgtMea = MAX(hgtMea, meaHgtAtTakeOff);
}
velPosObs[5] = -hgtMea; velPosObs[5] = -hgtMea;
} else { } else {
fuseHgtData = false; fuseHgtData = false;