SRV_Channel: remove default case in get_limit_pwm

All cases are currently handled, and this is something people should
probably think about if they're introducing another case!
This commit is contained in:
Peter Barker 2019-12-12 11:49:03 +11:00 committed by Andrew Tridgell
parent 72e6446204
commit 708a6f99a6

View File

@ -182,9 +182,9 @@ uint16_t SRV_Channel::get_limit_pwm(Limit limit) const
case Limit::MAX:
return reversed?servo_min:servo_max;
case Limit::ZERO_PWM:
default:
return 0;
}
return 0;
}
// return true if function is for a multicopter motor