AP_RCProtocol: prevent decoding past end of output array

this fixes test_sbus on clang
This commit is contained in:
Andrew Tridgell 2023-10-05 08:20:23 +11:00
parent 4709a1592f
commit c858b7201d
1 changed files with 1 additions and 1 deletions

View File

@ -97,7 +97,7 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values,
uint16_t chancount = SBUS_INPUT_CHANNELS;
decode_11bit_channels((const uint8_t*)(&frame[1]), SBUS_INPUT_CHANNELS, values,
decode_11bit_channels((const uint8_t*)(&frame[1]), max_values, values,
SBUS_TARGET_RANGE, SBUS_RANGE_RANGE, SBUS_SCALE_OFFSET);
/* decode switch channels if data fields are wide enough */