AP_HAL_ChibiOS: ensure dshot commands are send to all FMU channels when IOMCU is present
This commit is contained in:
parent
1fb6205439
commit
ea76c0bd01
@ -151,7 +151,7 @@ void RCOutput::update_channel_masks() {
|
||||
}
|
||||
|
||||
#if HAL_PWM_COUNT > 0
|
||||
for (uint8_t i=0; i<HAL_PWM_COUNT; i++) {
|
||||
for (uint8_t i=chan_offset; i<HAL_PWM_COUNT+chan_offset; i++) {
|
||||
switch (_dshot_esc_type) {
|
||||
case DSHOT_ESC_BLHELI:
|
||||
case DSHOT_ESC_BLHELI_S:
|
||||
|
Loading…
Reference in New Issue
Block a user