From 431b3c7160514bb5e259220a098a12f7963cda7a Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 21 Apr 2016 17:13:15 -0700 Subject: [PATCH] AP-TECS: constrain proportion to 0-1 for spdweight scale so it doesn't grow backup after land point --- libraries/AP_TECS/AP_TECS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 96ac01d8ae..6499d82866 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -761,7 +761,7 @@ void AP_TECS::_update_pitch(void) } else if (_flags.is_doing_auto_land) { if (_spdWeightLand < 0) { // use sliding scale from normal weight down to zero at landing - float scaled_weight = _spdWeight * (1.0f - _path_proportion); + float scaled_weight = _spdWeight * (1.0f - constrain_float(_path_proportion,0,1)); SKE_weighting = constrain_float(scaled_weight, 0.0f, 2.0f); } else { SKE_weighting = constrain_float(_spdWeightLand, 0.0f, 2.0f);