Skip to content

Conversation

@durka
Copy link

@durka durka commented Sep 4, 2024

If there are multiple components sending heartbeats, MAVProxy can get confused, lock onto the wrong one, and fail to receive any messages from the real autopilot.

There is a function in pymavlink, probably_vehicle_heartbeat, which can check for this since this commit ArduPilot/pymavlink@67669c3.

However, MAVProxy does not use probably_vehicle_heartbeat (at least not for this purpose), having its own version called heartbeat_is_from_autopilot in the link modoule.

The corresponding check is present in that function! However (x2), it incorrectly compares an integer against a string, which never matches.

This PR changes the strings to integer constants.

Disclaimer: I am employed by Exyn Technologies, an Ardupilot partner

Copy link
Contributor

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

LGTM.

Various places we take strings like this and manipulate them into the relevant integer enumeration value. I guess I might have copied this from one of those...

@peterbarker peterbarker merged commit 0503305 into ArduPilot:master Sep 5, 2024
@peterbarker
Copy link
Contributor

Merged, thanks!

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