Skip to content

AP_ADSB: avoid buffer overwrite in AP_ADSB_Sagetech_MXS#32656

Merged
tridge merged 1 commit into
ArduPilot:masterfrom
peterbarker:pr/sagetech-payload-len-check
Apr 15, 2026
Merged

AP_ADSB: avoid buffer overwrite in AP_ADSB_Sagetech_MXS#32656
tridge merged 1 commit into
ArduPilot:masterfrom
peterbarker:pr/sagetech-payload-len-check

Conversation

@peterbarker
Copy link
Copy Markdown
Contributor

Summary

Corrects notional buffer overflow in the MXS driver.

Testing (more checks increases chance of being merged)

  • Checked by a human programmer
  • Tested in SITL
  • Tested on hardware
  • Logs attached
  • Logs available on request
  • Autotest included

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.

Copy link
Copy Markdown
Contributor

@tpwrules tpwrules left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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).

Comment on lines +282 to +285
if (message_in.packet.payload_length > ARRAY_SIZE(message_in.packet.payload)) {
message_in.state = ParseState::WaitingFor_Start;
break;
}
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This can never be true, will Clang whine?

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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;
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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
@peterbarker peterbarker force-pushed the pr/sagetech-payload-len-check branch from 4a3307d to f1ba0c0 Compare April 3, 2026 23:40
Copy link
Copy Markdown
Contributor Author

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the review, @tpwrules

Comment on lines +282 to +285
if (message_in.packet.payload_length > ARRAY_SIZE(message_in.packet.payload)) {
message_in.state = ParseState::WaitingFor_Start;
break;
}
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

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;
Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wow. Just... wow.

I've re-instated this assignment and adjusted the payload-length check to allow for space in there.

Copy link
Copy Markdown
Contributor

@tpwrules tpwrules left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

@tridge tridge merged commit 2026840 into ArduPilot:master Apr 15, 2026
108 of 109 checks passed
@github-project-automation github-project-automation Bot moved this from ReadyForDevCall to Done in Peter's ArduPilot 4.8 Queue Apr 15, 2026
@peterbarker peterbarker deleted the pr/sagetech-payload-len-check branch April 16, 2026 04:53
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants