mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Remove unnecessary baro limiting
This commit is contained in:
parent
124f016e5b
commit
a5a25411da
|
@ -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;
|
||||||
|
|
Loading…
Reference in New Issue