AP_NavEKF2: 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 062a15ce11
commit ea6724aca5
2 changed files with 2 additions and 2 deletions

View File

@ -672,7 +672,7 @@ void NavEKF2_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 copter downwash 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

@ -1096,7 +1096,7 @@ void NavEKF2_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 copter downwash 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);
}
} else {