mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_ChibiOS: always normalize ESC channel when using iomcu
This commit is contained in:
parent
df19d143f2
commit
d69e6ae997
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user