From 1e0d271fef4d0b8a306b82f7a132c7b5a92d85d1 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 13 Mar 2024 18:10:26 +0000 Subject: [PATCH] AP_HAL_ChibiOS: always normalize ESC channel when using iomcu --- libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 89c25c026f746..cb1c04e29d574 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -757,7 +757,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c uint8_t normalized_chan = chan; #endif #if HAL_WITH_IO_MCU - if (iomcu_dshot) { + if (iomcu_enabled) { normalized_chan = chan + chan_offset; } #endif