AP_HAL_ChibiOS: always normalize ESC channel when using iomcu

This commit is contained in:
Andy Piper 2024-03-13 18:10:26 +00:00 committed by Peter Barker
parent e0b4143cad
commit 8a392be078
1 changed files with 1 additions and 1 deletions

View File

@ -757,7 +757,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c
uint8_t normalized_chan = chan; uint8_t normalized_chan = chan;
#endif #endif
#if HAL_WITH_IO_MCU #if HAL_WITH_IO_MCU
if (iomcu_dshot) { if (iomcu_enabled) {
normalized_chan = chan + chan_offset; normalized_chan = chan + chan_offset;
} }
#endif #endif