Browse Source

AP_RCProtocol: Fix out of bounds write, CID 308323 and 308333

mission-4.1.18
Michael du Breuil 7 years ago committed by Andrew Tridgell
parent
commit
4aff747b28
  1. 2
      libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp
  2. 2
      libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp

2
libraries/AP_RCProtocol/AP_RCProtocol_SBUS.cpp

@ -221,7 +221,7 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1) @@ -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

2
libraries/AP_RCProtocol/AP_RCProtocol_SRXL.cpp

@ -62,7 +62,7 @@ void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1) @@ -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…
Cancel
Save