AP_ESC_TELEM: solved the logical error in grouping of escs into 4

This commit is contained in:
aditya 2023-10-01 00:57:55 +05:30 committed by Randy Mackay
parent c9f7a3c03d
commit 9abcd6b7ca
1 changed files with 5 additions and 2 deletions

View File

@ -318,8 +318,11 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)
const uint32_t now_us = AP_HAL::micros();
// loop through groups of 4 ESCs
const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS - 1);
const uint8_t num_idx = ESC_TELEM_MAX_ESCS / 4;
const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1);
// ensure we send out partially-full groups:
const uint8_t num_idx = (ESC_TELEM_MAX_ESCS + 3) / 4;
for (uint8_t idx = 0; idx < num_idx; idx++) {
const uint8_t i = (next_idx + idx) % num_idx;