AP_NavEKF3: don't limit baro change when we are in fixed wing mode

This commit is contained in:
Andrew Tridgell 2021-05-29 12:01:16 +10:00 committed by Randy Mackay
parent ea6724aca5
commit dc9435a88d
2 changed files with 2 additions and 2 deletions

View File

@ -737,7 +737,7 @@ void NavEKF3_core::readBaroData()
// 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 (dal.get_takeoff_expected()) {
if (dal.get_takeoff_expected() && !assume_zero_sideslip()) {
baroDataNew.hgt = MAX(baroDataNew.hgt, meaHgtAtTakeOff);
}

View File

@ -1182,7 +1182,7 @@ void NavEKF3_core::selectHeightForFusion()
}
// 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()) {
if (motorsArmed && dal.get_takeoff_expected() && !assume_zero_sideslip()) {
hgtMea = MAX(hgtMea, meaHgtAtTakeOff);
}
velPosObs[5] = -hgtMea;