AC_AttControl: allow MOT_THR_MIX_MAX to be 2.0

The parameter description maximum of 0.9 should keep most users from
setting this parameter above 0.9 but there are rare cases for very high powered copters with low hover-throttle values where setting as high as 2.0 improves attitude control
This commit is contained in:
Leonard Hall 2016-11-30 12:22:13 +09:00 committed by Randy Mackay
parent d5faf977c8
commit 7c6bdfb95c

View File

@ -238,7 +238,9 @@ void AC_AttitudeControl_Multi::parameter_sanity_check()
if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) {
_thr_mix_min = AC_ATTITUDE_CONTROL_MIN_DEFAULT;
}
if (_thr_mix_max < 0.5f || _thr_mix_max > 0.9f) {
if (_thr_mix_max < 0.5f || _thr_mix_max > 2.0f) {
// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 2.0
// which can be useful for very high powered copters with very low hover throttle
_thr_mix_max = AC_ATTITUDE_CONTROL_MAX_DEFAULT;
}
if (_thr_mix_min > _thr_mix_max) {