mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_RCProtocol: Fix out of bounds write, CID 308323 and 308333
This commit is contained in:
parent
430ed9bd3d
commit
4aff747b28
@ -221,7 +221,7 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
goto reset;
|
||||
}
|
||||
|
||||
if (byte_ofs > 25) {
|
||||
if (byte_ofs >= ARRAY_SIZE(sbus_state.bytes)) {
|
||||
goto reset;
|
||||
}
|
||||
// pull in the high bits
|
||||
|
@ -62,7 +62,7 @@ void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
|
||||
byte_ofs = srxl_state.bit_ofs/10;
|
||||
bit_ofs = srxl_state.bit_ofs%10;
|
||||
if (byte_ofs > SRXL_FRAMELEN_MAX) {
|
||||
if (byte_ofs >= SRXL_FRAMELEN_MAX) {
|
||||
goto reset;
|
||||
}
|
||||
// pull in the high bits
|
||||
|
Loading…
Reference in New Issue
Block a user