diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 6fe46c1bab..c02336a536 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -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); }