AC_AttControl: remove redundant parameter set

This commit is contained in:
Randy Mackay 2017-01-17 14:55:43 +09:00
parent 36b6218e31
commit 189b766f2b

View File

@ -248,23 +248,18 @@ void AC_AttitudeControl_Multi::parameter_sanity_check()
if (_thr_mix_man < 0.1f || _thr_mix_man > 4.0f) { if (_thr_mix_man < 0.1f || _thr_mix_man > 4.0f) {
// parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0 // parameter description recommends thr-mix-man be no higher than 0.9 but we allow up to 4.0
// which can be useful for very high powered copters with very low hover throttle // which can be useful for very high powered copters with very low hover throttle
_thr_mix_man = AC_ATTITUDE_CONTROL_MAN_DEFAULT;
_thr_mix_man.set_and_save(AC_ATTITUDE_CONTROL_MAN_DEFAULT); _thr_mix_man.set_and_save(AC_ATTITUDE_CONTROL_MAN_DEFAULT);
} }
if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) { if (_thr_mix_min < 0.1f || _thr_mix_min > 0.25f) {
_thr_mix_min = AC_ATTITUDE_CONTROL_MIN_DEFAULT;
_thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT); _thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);
} }
if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) { if (_thr_mix_max < 0.5f || _thr_mix_max > AC_ATTITUDE_CONTROL_MAX) {
// parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0 // parameter description recommends thr-mix-max be no higher than 0.9 but we allow up to 5.0
// which can be useful for very high powered copters with very low hover throttle // which can be useful for very high powered copters with very low hover throttle
_thr_mix_max = AC_ATTITUDE_CONTROL_MAX_DEFAULT;
_thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT); _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);
} }
if (_thr_mix_min > _thr_mix_max) { if (_thr_mix_min > _thr_mix_max) {
_thr_mix_min = AC_ATTITUDE_CONTROL_MIN_DEFAULT;
_thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT); _thr_mix_min.set_and_save(AC_ATTITUDE_CONTROL_MIN_DEFAULT);
_thr_mix_max = AC_ATTITUDE_CONTROL_MAX_DEFAULT;
_thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT); _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT);
} }
} }