Skip to content

Commit

Permalink
AP_HAL_ChibiOS: always normalize ESC channel when using iomcu
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed Mar 13, 2024
1 parent 12f3270 commit 1e0d271
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 1e0d271

Please sign in to comment.