Skip to content

AP_ADSB: correct copying of callsign in Sagetech XP ADSB driver#32655

Merged
peterbarker merged 1 commit into
ArduPilot:masterfrom
peterbarker:pr/sagetech-xp-fix
Apr 20, 2026
Merged

AP_ADSB: correct copying of callsign in Sagetech XP ADSB driver#32655
peterbarker merged 1 commit into
ArduPilot:masterfrom
peterbarker:pr/sagetech-xp-fix

Conversation

@peterbarker
Copy link
Copy Markdown
Contributor

Summary

this appeared to be overwriting all of the data at the start of the mavlink packet, rather than overwriting the callsign within the packet.

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

This appears to have been DOA.

This issue was responsibly disclosed to the ArduPilot development team by secmate.dev.

@peterbarker peterbarker marked this pull request as ready for review April 9, 2026 00:32
@peterbarker peterbarker moved this to ReadyForDevCall in Peter's ArduPilot 4.8 Queue Apr 9, 2026
Comment thread libraries/AP_ADSB/AP_ADSB_Sagetech.cpp Outdated
if (msg.payload[16] != 0) {
// if string is non-null, consider it valid
memcpy(&vehicle.info, &msg.payload[16], 8);
memcpy(&vehicle.info.callsign, &msg.payload[16], ARRAY_SIZE(vehicle.info.callsign)-1); // "The callsign, 8+null" means we subtract one here
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

I know that currently ARRAY_SIZE(vehicle.info.callsign)-1) is 8. But that could change, I guess its 8 bytes in the message payload. Should this be MIN(8, ARRAY_SIZE(vehicle.info.callsign)-1)?

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.

I know that currently ARRAY_SIZE(vehicle.info.callsign)-1) is 8. But that could change, I guess its 8 bytes in the message payload. Should this be MIN(8, ARRAY_SIZE(vehicle.info.callsign)-1)?

Yeah. I considered it. Thought it might be going a bit far given the one to worry about would be the wire format!

I've added the patch, thanks!

Comment thread libraries/AP_ADSB/AP_ADSB_Sagetech.cpp Outdated
if (msg.payload[16] != 0) {
// if string is non-null, consider it valid
memcpy(&vehicle.info, &msg.payload[16], 8);
memcpy(&vehicle.info.callsign, &msg.payload[16], MIN(ARRAY_SIZE(vehicle.info.callsign)-1, 8)); // "The callsign, 8+null" means we subtract one here
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.

maybe move the comment to the line above?

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.

Done

this appeared to be overwriting all of the data at the start of the mavlink packet, rather than overwriting the callsign within the packet.
@peterbarker peterbarker merged commit c627a34 into ArduPilot:master Apr 20, 2026
109 checks passed
@github-project-automation github-project-automation Bot moved this from ReadyForDevCall to Done in Peter's ArduPilot 4.8 Queue Apr 20, 2026
@peterbarker peterbarker deleted the pr/sagetech-xp-fix branch April 20, 2026 10:59
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

5 participants