Browse Source

AP_RCProtocol: fixed bug in FPort parser

if we got invalid frame->type values we would overrun the buffer and
cause memory corruption. This was the cause of the bug Polarijet found
c415-sdk
Andrew Tridgell 5 years ago
parent
commit
a1069d85cb
  1. 7
      libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp

7
libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp

@ -322,6 +322,10 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b) @@ -322,6 +322,10 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b)
(frame->type == FPORT_TYPE_DOWNLINK && frame->len != FRAME_LEN_DOWNLINK)) {
goto reset;
}
if (frame->type != FPORT_TYPE_CONTROL && frame->type != FPORT_TYPE_DOWNLINK) {
// invalid type
goto reset;
}
}
if (frame->type == FPORT_TYPE_CONTROL && byte_input.ofs == FRAME_LEN_CONTROL + 4) {
@ -335,6 +339,9 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b) @@ -335,6 +339,9 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b)
}
goto reset;
}
if (byte_input.ofs == sizeof(byte_input.buf)) {
goto reset;
}
return;
reset:

Loading…
Cancel
Save