diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index e28c198c24..7f50b0e1dd 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -500,10 +500,10 @@ RCOutput::pwm_group *RCOutput::find_chan(uint8_t chan, uint8_t &group_idx) /* * return mask of channels that must be disabled because they share a group with a digital channel */ -uint16_t RCOutput::get_disabled_channels(uint16_t digital_mask) +uint32_t RCOutput::get_disabled_channels(uint32_t digital_mask) { - uint16_t dmask = (digital_mask >> chan_offset); - uint16_t disabled_chan_mask = 0; + uint32_t dmask = (digital_mask >> chan_offset); + uint32_t disabled_chan_mask = 0; for (auto &group : pwm_group_list) { bool digital_group = false; for (uint8_t j = 0; j < 4; j++) { @@ -615,7 +615,7 @@ void RCOutput::push_local(void) if (active_fmu_channels == 0) { return; } - uint16_t outmask = (1U<> chan_offset); // we now need to reconfigure the DMA channels since they are affected by the value of the mask diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index 5fefc7ee6e..c81159f1f9 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -50,7 +50,7 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha group.dshot_waiter = rcout_thread_ctx; bool bdshot_telem = false; #ifdef HAL_WITH_BIDIR_DSHOT - uint16_t active_channels = group.ch_mask & group.en_mask; + uint32_t active_channels = group.ch_mask & group.en_mask; // no need to get the input capture lock group.bdshot.enabled = false; if ((_bdshot.mask & active_channels) == active_channels) {