AP_Motors: don't setup oneshot for a zero output mask

This commit is contained in:
Andrew Tridgell 2016-05-26 12:18:03 +10:00
parent ec0a80b6f4
commit a44b0e0011

View File

@ -107,7 +107,8 @@ void AP_Motors::rc_set_freq(uint32_t mask, uint16_t freq_hz)
hal.rcout->set_freq(mask, freq_hz);
if ((_pwm_type == PWM_TYPE_ONESHOT ||
_pwm_type == PWM_TYPE_ONESHOT125) &&
freq_hz > 50) {
freq_hz > 50 &&
mask != 0) {
// tell HAL to do immediate output
hal.rcout->set_output_mode(AP_HAL::RCOutput::MODE_PWM_ONESHOT);
}