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

This commit is contained in:
Andrew Tridgell 2018-08-07 13:24:34 +10:00
parent 996278e5b6
commit 9c4e95a982
1 changed files with 4 additions and 0 deletions

View File

@ -222,6 +222,10 @@ void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
goto reset;
}
if (byte_ofs >= ARRAY_SIZE(sbus_state.bytes)) {
goto reset;
}
// pull in the high bits
sbus_state.bytes[byte_ofs] |= ((1U<<bits_s0)-1) << bit_ofs;
sbus_state.bit_ofs += bits_s0;