AP_GPS: SBF: Reject short packets early, allow 256 byte long messages to be decoded

This commit is contained in:
Michael du Breuil 2017-09-04 17:09:03 -07:00 committed by Andrew Tridgell
parent 048dfee68a
commit be371e09f9
2 changed files with 8 additions and 7 deletions

View File

@ -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);

View File

@ -159,7 +159,7 @@ private:
msg4001 msg4001u;
msg4014 msg4014u;
msg5908 msg5908u;
uint8_t bytes[128];
uint8_t bytes[256];
};
struct sbf_msg_parser_t