diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 5da5b9dac651ce..3dacf98fe913d8 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -321,9 +321,8 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) 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 % 4 == 0) ? ESC_TELEM_MAX_ESCS / 4 : (ESC_TELEM_MAX_ESCS / 4) + 1; + 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;