Fix MAVLink message bounds validation vulnerabilities#14067
Fix MAVLink message bounds validation vulnerabilities#14067DonLakeFlyer merged 1 commit intomasterfrom
Conversation
Build ResultsPlatform Status
All builds passed. Pre-commit
Pre-commit hooks: 32 passed, 78 failed, 10 skipped. Test Resultslinux-sanitizers: 52 passed, 0 skipped linux_gcc_64: 52 passed, 0 skipped Total: 104 passed, 0 skipped Code CoverageCoverage: N/A No baseline available for comparison Artifact Sizes
No baseline available for comparison Updated: 2026-03-06 04:23:26 UTC • Triggered by: MacOS |
| _imageHandshake = {}; | ||
| break; | ||
| } | ||
| if (_imageHandshake.payload > sizeof(mavlink_encapsulated_data_t::data)) { |
There was a problem hiding this comment.
sizeof(mavlink_encapsulated_data_t::data) is not valid C++ for a non-static member; this will fail to compile. Use sizeof(encapsulatedData.data) (or an equivalent sizeof(((mavlink_encapsulated_data_t*)nullptr)->data)) to compare against the ENCAPSULATED_DATA data array size.
| if (_imageHandshake.payload > sizeof(mavlink_encapsulated_data_t::data)) { | |
| if (_imageHandshake.payload > sizeof(((mavlink_encapsulated_data_t*)nullptr)->data)) { |
| break; | ||
| } | ||
|
|
||
| _imageBytes.resize(_imageHandshake.size, '\0'); |
There was a problem hiding this comment.
QByteArray::resize only takes a single size argument; resize(_imageHandshake.size, '\0') will not compile. If you want the buffer zero-initialized, use fill('\0', _imageHandshake.size) or assign a QByteArray(_imageHandshake.size, '\0') after the validation checks.
| _imageBytes.resize(_imageHandshake.size, '\0'); | |
| _imageBytes.fill('\0', _imageHandshake.size); |
Harden MAVLink message handlers against malicious or malformed payloads that could trigger out-of-bounds memory access. ImageProtocolManager (GHSA-v5rc-wh3c-c4cw): - Validate DATA_TRANSMISSION_HANDSHAKE fields (size, payload, packets) before allocating the image buffer - Enforce 1 MB upper bound on image size - Reject payload values exceeding ENCAPSULATED_DATA data[253] array size - Pre-allocate image buffer to declared size instead of growing via unchecked indexed writes - Replace byte-by-byte copy loop with bounds-clamped memcpy - Cast seqnr to uint32_t before multiplication to prevent overflow Vehicle (LOG_DATA): - Add bounds check on log.count against sizeof(log.data) before emitting the signal, preventing downstream consumers from reading past the 90-byte data array FTPManager (FILE_TRANSFER_PROTOCOL): - Validate hdr.size against sizeof(request->data) at the single message entry point, protecting all downstream handlers (burst read, list directory, fill missing blocks) from reading past the 239-byte data array Fixes: GHSA-v5rc-wh3c-c4cw
bae5113 to
d478b64
Compare
Harden MAVLink message handlers against malicious or malformed payloads that could trigger out-of-bounds memory access.
Fixes https://github.com/mavlink/qgroundcontrol/security/advisories/GHSA-v5rc-wh3c-c4cw
ImageProtocolManager (
GHSA-v5rc-wh3c-c4cw)DATA_TRANSMISSION_HANDSHAKEfields (size,payload,packets) before allocating the image bufferpayloadvalues exceedingENCAPSULATED_DATAdata[253]array sizememcpyseqnrtouint32_tbefore multiplication to prevent overflowVehicle (
LOG_DATA)log.countagainstsizeof(log.data)before emitting the signal, preventing downstream consumers from reading past the 90-byte data arrayFTPManager (
FILE_TRANSFER_PROTOCOL)hdr.sizeagainstsizeof(request->data)at the single message entry point, protecting all downstream handlers (burst read, list directory, fill missing blocks) from reading past the 239-byte data array