mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 13:08:34 -04:00
AP_BLHeli: normalize ESC index correctly with iomcu
This commit is contained in:
parent
6f6e4d458a
commit
c557ba38e5
@ -1469,7 +1469,7 @@ void AP_BLHeli::read_telemetry_packet(void)
|
||||
|
||||
uint8_t normalized_motor_idx = motor_idx - chan_offset;
|
||||
#if HAL_WITH_IO_MCU
|
||||
if (AP_BoardConfig::io_dshot()) {
|
||||
if (AP_BoardConfig::io_enabled()) {
|
||||
normalized_motor_idx = motor_idx;
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user