mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: fixed crc memory range error in CRSF
this fixes a crash bug that caused a watchdog for Henry on a F765-Wing. The bug happens with corrupt serial data causing an underflow in the length argument to the crc call
This commit is contained in:
parent
01b0e0c27c
commit
427384eb11
|
@ -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);
|
||||
|
|
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue