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