AP_BLHeli: ensure correct rotation through telemetry ESCs

This commit is contained in:
Andy Piper 2021-07-15 19:21:54 +01:00 committed by Andrew Tridgell
parent 48b8fdfd48
commit ca477d09ed
1 changed files with 2 additions and 2 deletions

View File

@ -1495,7 +1495,7 @@ void AP_BLHeli::log_bidir_telemetry(void)
// ask the next ESC for telemetry
uint8_t idx_pos = last_telem_esc;
uint8_t idx = (idx_pos + 1) % num_motors;
for (; idx != idx_pos; idx = (idx_pos + 1) % num_motors) {
for (; idx != idx_pos; idx = (idx + 1) % num_motors) {
if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {
break;
}
@ -1564,7 +1564,7 @@ void AP_BLHeli::update_telemetry(void)
// ask the next ESC for telemetry
uint8_t idx_pos = last_telem_esc;
uint8_t idx = (idx_pos + 1) % num_motors;
for (; idx != idx_pos; idx = (idx_pos + 1) % num_motors) {
for (; idx != idx_pos; idx = (idx + 1) % num_motors) {
if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {
break;
}