Skip to content

Commit

Permalink
AP_HAL_ChibiOS: correctly check for channel enablement on iomcu
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed Sep 4, 2024
1 parent ff2c64e commit e5d26a5
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel)
// we need to switch every output on the same input channel to avoid
// spurious line changes
for (uint8_t i = 0; i<4; i++) {
if (group.chan[i] == CHAN_DISABLED) {
if (!group.is_chan_enabled(i)) {
continue;
}
if (group.bdshot.telem_tim_ch[telem_channel] == group.bdshot.telem_tim_ch[i]) {
Expand Down Expand Up @@ -250,7 +250,7 @@ void RCOutput::bdshot_receive_pulses_DMAR_f1(pwm_group* group)
// we need to switch every input on the same input channel to allow
// the ESCs to drive the lines
for (uint8_t i = 0; i<4; i++) {
if (group->chan[i] == CHAN_DISABLED) {
if (!group->is_chan_enabled(i)) {
continue;
}
if (group->bdshot.telem_tim_ch[curr_ch] == group->bdshot.telem_tim_ch[i]) {
Expand Down

0 comments on commit e5d26a5

Please sign in to comment.