mirror of https://github.com/ArduPilot/ardupilot
AP_BLHeli: ensure correct rotation through telemetry ESCs
This commit is contained in:
parent
3cee86e63f
commit
74a8891099
|
@ -1494,7 +1494,7 @@ void AP_BLHeli::log_bidir_telemetry(void)
|
||||||
// ask the next ESC for telemetry
|
// ask the next ESC for telemetry
|
||||||
uint8_t idx_pos = last_telem_esc;
|
uint8_t idx_pos = last_telem_esc;
|
||||||
uint8_t idx = (idx_pos + 1) % num_motors;
|
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])) {
|
if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -1563,7 +1563,7 @@ void AP_BLHeli::update_telemetry(void)
|
||||||
// ask the next ESC for telemetry
|
// ask the next ESC for telemetry
|
||||||
uint8_t idx_pos = last_telem_esc;
|
uint8_t idx_pos = last_telem_esc;
|
||||||
uint8_t idx = (idx_pos + 1) % num_motors;
|
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])) {
|
if (SRV_Channels::have_digital_outputs(1U << motor_map[idx])) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue