From 2cba60c7318e827484d9fd8079035cfa3ba1cf93 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Tue, 28 Apr 2015 07:02:23 +1000 Subject: [PATCH] AP_NavEKF: Decouple takeoff ground effect compensation from arm transtion Thsi fixes a potential bug where the vehicle could land at a lower location without disarming and re-enter ground effect takeoff mode wiht a baro height floor above the current altitude, causing unpredictable height gain --- libraries/AP_NavEKF/AP_NavEKF.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index b627fd2707..72a9926efd 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -4177,8 +4177,8 @@ void NavEKF::readHgtData() // filtered baro data used to provide a reference for takeoff // it is is reset to last height measurement on disarming in performArmingChecks() - if (!vehicleArmed || !getTakeoffExpected()) { - static const float gndHgtFiltTC = 1.0f; + if (!getTakeoffExpected()) { + static const float gndHgtFiltTC = 0.5f; static const float dtBaro = msecHgtAvg*1.0e-3f; float alpha = constrain_float(dtBaro / (dtBaro+gndHgtFiltTC),0.0f,1.0f); meaHgtAtTakeOff += (hgtMea-meaHgtAtTakeOff)*alpha;