mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: SBF: Reject short packets early, allow 256 byte long messages to be decoded
This commit is contained in:
parent
697e856b12
commit
c39ae3392e
@ -130,6 +130,13 @@ AP_GPS_SBF::parse(uint8_t temp)
|
||||
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
|
||||
Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
|
||||
}
|
||||
if (sbf_msg.length < 8) {
|
||||
Debug("bad packet length=%u\n", (unsigned)sbf_msg.length);
|
||||
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
|
||||
crc_error_counter++; // this is a probable buffer overflow, but this
|
||||
// indicates not enough bytes to do a crc
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case sbf_msg_parser_t::DATA:
|
||||
if (sbf_msg.read < sizeof(sbf_msg.data)) {
|
||||
@ -142,12 +149,6 @@ AP_GPS_SBF::parse(uint8_t temp)
|
||||
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
|
||||
break;
|
||||
}
|
||||
if (sbf_msg.length < 8) {
|
||||
Debug("length error %u\n", (unsigned)sbf_msg.length);
|
||||
sbf_msg.sbf_state = sbf_msg_parser_t::PREAMBLE1;
|
||||
crc_error_counter++;
|
||||
break;
|
||||
}
|
||||
uint16_t crc = crc16_ccitt((uint8_t*)&sbf_msg.blockid, 2, 0);
|
||||
crc = crc16_ccitt((uint8_t*)&sbf_msg.length, 2, crc);
|
||||
crc = crc16_ccitt((uint8_t*)&sbf_msg.data, sbf_msg.length - 8, crc);
|
||||
|
@ -130,7 +130,7 @@ private:
|
||||
msg4007 msg4007u;
|
||||
msg4001 msg4001u;
|
||||
msg4014 msg4014u;
|
||||
uint8_t bytes[128];
|
||||
uint8_t bytes[256];
|
||||
};
|
||||
|
||||
struct sbf_msg_parser_t
|
||||
|
Loading…
Reference in New Issue
Block a user