AP_Motors: ensure _pwm_min and _pwm_max are not equal

AP_Motors: adjust check_mot_pwm_params for clarity
This commit is contained in:
Peter Barker 2020-01-30 12:23:51 +11:00 committed by Randy Mackay
parent 346471258b
commit c4ed6d0e96

View File

@ -486,8 +486,19 @@ int16_t AP_MotorsMulticopter::get_pwm_output_max() const
// parameter checks for MOT_PWM_MIN/MAX, returns true if parameters are valid
bool AP_MotorsMulticopter::check_mot_pwm_params() const
{
if ((_pwm_min == 0 && _pwm_max != 0) || (_pwm_min != 0 && _pwm_max == 0) ||
(_pwm_min < 0 || _pwm_max < 0) || (_pwm_min > _pwm_max)) {
// both must be zero or both non-zero:
if (_pwm_min == 0 && _pwm_max != 0) {
return false;
}
if (_pwm_min != 0 && _pwm_max == 0) {
return false;
}
// sanity says that minimum should be less than maximum:
if (_pwm_min != 0 && _pwm_min >= _pwm_max) {
return false;
}
// negative values are out-of-range:
if (_pwm_min < 0 || _pwm_max < 0) {
return false;
}
return true;