AP_BLHeli: normalize ESC index correctly with iomcu

This commit is contained in:
Andy Piper 2025-01-04 10:43:33 +00:00 committed by Andrew Tridgell
parent 6fa3d8e18b
commit 417a8a5147

View File

@ -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