mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP-TECS: constrain proportion to 0-1 for spdweight scale so it doesn't grow backup after land point
This commit is contained in:
parent
f12658dd20
commit
431b3c7160
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user