From a1069d85cb22b622486a0303095dc209e3f2f914 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 20 Mar 2020 09:44:13 +1100 Subject: [PATCH] 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 --- libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index 8f15407435..8973387095 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -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) } goto reset; } + if (byte_input.ofs == sizeof(byte_input.buf)) { + goto reset; + } return; reset: