Skip to content

Commit

Permalink
MAVLinkInterface.cs: remove 0.9 from mavlink parser
Browse files Browse the repository at this point in the history
treating 'U' as a header marker byte leads to the problem that we will accidentally consume parts of a valid packet after receiving a "plain text" message.

This is particularly problematic in ArduPilot's config-error-loop, as we emit the problem as both statustext and raw "line noise" to the GCS; the statustext is lost, mneaning the user doesn't get any specific error message from the autopilot, just "in config error loop".

Co-authored-by: Bob Long <[email protected]>
Co-authored-by: Michelle Rossouw <[email protected]>
  • Loading branch information
3 people authored and meee1 committed Feb 3, 2025
1 parent b2c5347 commit 06378f1
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions ExtLibs/ArduPilot/Mavlink/MAVLinkInterface.cs
Original file line number Diff line number Diff line change
Expand Up @@ -4745,7 +4745,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
}

// check if looks like a mavlink packet and check for exclusions and write to console
if (buffer[0] != MAVLINK_STX_MAVLINK1 && buffer[0] != 'U' && buffer[0] != MAVLINK_STX)
if (buffer[0] != MAVLINK_STX_MAVLINK1 && buffer[0] != MAVLINK_STX)
{
if (buffer[0] >= 0x20 && buffer[0] <= 127 || buffer[0] == '\n' || buffer[0] == '\r')
{
Expand Down Expand Up @@ -4787,7 +4787,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
Console.WriteLine(DateTime.Now.Millisecond + " SR2 " + BaseStream?.BytesToRead);

// check for a header
if (buffer[0] == MAVLINK_STX_MAVLINK1 || buffer[0] == MAVLINK_STX || buffer[0] == 'U')
if (buffer[0] == MAVLINK_STX_MAVLINK1 || buffer[0] == MAVLINK_STX)
{
var mavlinkv2 = buffer[0] == MAVLINK_STX ? true : false;

Expand Down Expand Up @@ -5097,7 +5097,7 @@ public async Task<MAVLinkMessage> readPacketAsync()
packetSeemValid = false;
//The following IF had to be splitted to accomodate the new place of Readlock end.
//packetSeemValid helps it.
if ((message.header == 'U' || message.header == MAVLINK_STX_MAVLINK1 ||
if ((message.header == MAVLINK_STX_MAVLINK1 ||
message.header == MAVLINK_STX) &&
buffer.Length >= message.payloadlength)
{
Expand Down Expand Up @@ -6563,15 +6563,15 @@ private MAVLinkMessage readlogPacketMavlink()
{
case 0:
byte0 = tempb;
if (byte0 != 'U' && byte0 != MAVLINK_STX_MAVLINK1 && byte0 != MAVLINK_STX)
if (byte0 != MAVLINK_STX_MAVLINK1 && byte0 != MAVLINK_STX)
{
log.DebugFormat("logread - lost sync byte {0} pos {1}", byte0,
logplaybackfile.BaseStream.Position);
// seek to next valid
do
{
byte0 = logplaybackfile.ReadByte();
} while (byte0 != 'U' && byte0 != MAVLINK_STX_MAVLINK1 && byte0 != MAVLINK_STX);
} while (byte0 != MAVLINK_STX_MAVLINK1 && byte0 != MAVLINK_STX);

a = 1;
continue;
Expand Down

0 comments on commit 06378f1

Please sign in to comment.