mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_RCProtocol: prevent decoding past end of output array
this fixes test_sbus on clang
This commit is contained in:
parent
4709a1592f
commit
c858b7201d
@ -97,7 +97,7 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values,
|
|||||||
|
|
||||||
uint16_t chancount = SBUS_INPUT_CHANNELS;
|
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);
|
SBUS_TARGET_RANGE, SBUS_RANGE_RANGE, SBUS_SCALE_OFFSET);
|
||||||
|
|
||||||
/* decode switch channels if data fields are wide enough */
|
/* decode switch channels if data fields are wide enough */
|
||||||
|
Loading…
Reference in New Issue
Block a user