diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index c5d3d98ce5..34d96c5f54 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -80,7 +80,7 @@ void RCOutput::init() chMtxObjectInit(&trigger_mutex); // setup default output rate of 50Hz - set_freq(0xFFFF, 50); + set_freq(0xFFFF ^ ((1U< 50) { - io_fast_channel_mask = chmask; + io_fast_channel_mask |= io_chmask; + } else { + io_fast_channel_mask &= ~io_chmask; + } + if (io_chmask) { + iomcu.set_freq(io_fast_channel_mask, freq_hz); } - iomcu.set_freq(chmask, freq_hz); } #endif @@ -206,9 +211,6 @@ void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) fast_channel_mask |= group.ch_mask; } } - if (chmask != update_mask) { - hal.console->printf("RCOutput: Failed to set PWM frequency req %x set %x\n", (unsigned)chmask, (unsigned)update_mask); - } } /*