From 0156d846f1ea050692fa8d1cd2ee575754f05c80 Mon Sep 17 00:00:00 2001 From: priseborough Date: Thu, 20 Nov 2014 21:45:57 +1100 Subject: [PATCH] AP_NavEKF: Increase height at which nav gain reduction starts Compensates for optical flow induced noise increase with height. --- libraries/AP_NavEKF/AP_NavEKF.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index a18439261e..7f1f93d159 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -3630,7 +3630,7 @@ void NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScal // allow 1.0 rad/sec margin for angular motion ekfGndSpdLimit = max((_maxFlowRate - 1.0f), 0.0f) * max((flowStates[1] - state.position[2]), 0.1f); // use standard gains up to 5.0 metres height and reduce above that - ekfNavVelGainScaler = 3.0f / max((flowStates[1] - state.position[2]),3.0f); + ekfNavVelGainScaler = 4.0f / max((flowStates[1] - state.position[2]),4.0f); } else { ekfGndSpdLimit = 400.0f; //return 80% of max filter speed ekfNavVelGainScaler = 1.0f;