AP_ADSB: avoid buffer overwrite in AP_ADSB_Sagetech_MXS#32656
Conversation
tpwrules
left a comment
There was a problem hiding this comment.
I think the right solution is to embiggen the buffer by one or reject packets > 254 bytes (I don't know if there are any with 254 or 255 bytes).
| if (message_in.packet.payload_length > ARRAY_SIZE(message_in.packet.payload)) { | ||
| message_in.state = ParseState::WaitingFor_Start; | ||
| break; | ||
| } |
There was a problem hiding this comment.
This can never be true, will Clang whine?
There was a problem hiding this comment.
Well, it can't be true with the current code. But I doubt the true maximum payload length in these packets is 255 bytes (and we could notionally set it to the maximum payload length we actually handle the message for. So the sanity check makes sense.
| message_in.state = ParseState::WaitingFor_Start; | ||
| if (message_in.checksum == data) { | ||
| // append the checksum to the payload and zero out the payload index | ||
| message_in.packet.payload[message_in.index] = data; |
There was a problem hiding this comment.
It sure looks like the SDK expects the checksum to be the last byte and will read one more than the length to get it. But I don't know if there are any full length packets.
There was a problem hiding this comment.
Wow. Just... wow.
I've re-instated this assignment and adjusted the payload-length check to allow for space in there.
we were not bounds-checking the off-wire length, and then reading many bytes into a target buffer based on it. Do the bounds check. Also remove the writing of the checksum into the payload buffer - this was the notional 1-byte overwrite
4a3307d to
f1ba0c0
Compare
peterbarker
left a comment
There was a problem hiding this comment.
Thanks for the review, @tpwrules
| if (message_in.packet.payload_length > ARRAY_SIZE(message_in.packet.payload)) { | ||
| message_in.state = ParseState::WaitingFor_Start; | ||
| break; | ||
| } |
There was a problem hiding this comment.
Well, it can't be true with the current code. But I doubt the true maximum payload length in these packets is 255 bytes (and we could notionally set it to the maximum payload length we actually handle the message for. So the sanity check makes sense.
| message_in.state = ParseState::WaitingFor_Start; | ||
| if (message_in.checksum == data) { | ||
| // append the checksum to the payload and zero out the payload index | ||
| message_in.packet.payload[message_in.index] = data; |
There was a problem hiding this comment.
Wow. Just... wow.
I've re-instated this assignment and adjusted the payload-length check to allow for space in there.
Summary
Corrects notional buffer overflow in the MXS driver.
Testing (more checks increases chance of being merged)
Description
we were not bounds-checking this value, and then reading many bytes into a target buffer based on it.
Do the bounds check.
The payload buffer is 255 bytes - so this is a one-byte overflow.
This issue was responsibly disclosed to the ArduPilot development team by secmate.dev.