diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index d8a4fecb2b..b17a21e62f 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -243,6 +243,11 @@ void PX4RCOutput::_timer_tick(void) { uint32_t now = hal.scheduler->micros(); + if ((_enabled_channels & ((1U<<_servo_count)-1)) == 0) { + // no channels enabled + goto update_pwm; + } + // always send at least at 20Hz, otherwise the IO board may think // we are dead if (now - _last_output > 50000) {