diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp index e9bd9910c8..a2372744a9 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp @@ -276,6 +276,11 @@ bool AP_RCProtocol_CRSF::check_frame(uint32_t timestamp_us) return false; } + if (_frame.length + CRSF_HEADER_LEN < _frame_ofs) { + // invalid short frame + return false; + } + // decode whatever we got and expect if (_frame_ofs >= _frame.length + CRSF_HEADER_LEN) { const uint8_t crc = crc8_dvb_s2_update(0, &_frame_bytes[CRSF_HEADER_LEN], _frame.length - 1); diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h index a01ba30603..aaaf0fb2bf 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.h @@ -33,6 +33,7 @@ #define CRSF_FRAMELEN_MAX 64U // maximum possible framelength #define CRSF_HEADER_LEN 2U // header length #define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CRSF_HEADER_LEN) // maximum size of the frame length field in a packet +#define CRSF_FRAME_LENGTH_MIN 2 // min value for _frame.length #define CRSF_BAUDRATE 416666U #define ELRS_BAUDRATE 420000U #define CRSF_TX_TIMEOUT 500000U // the period after which the transmitter is considered disconnected (matches copters failsafe)