mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_HAL_ChibiOS: correctly check for channel enablement on iomcu
This commit is contained in:
parent
ff2c64e4b1
commit
e5d26a579d
@ -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]) {
|
||||
@ -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]) {
|
||||
|
Loading…
Reference in New Issue
Block a user