Severe Mavlink packet loss on simple example code [solved]

Hello.

[1]
Terminal Output of MAVLink Message Reception(Mavlink Example code) :

file descriptor opened as 3
Received message ID  : 125
Received message Sequence : 40
Received message ID  : 36
Received message Sequence : 43
Received message ID  : 65
Received message Sequence : 44
Received message ID  : 74
Received message Sequence : 56
Received message ID  : 125
Received message Sequence : 65
Received message ID  : 42
Received message Sequence : 67
Received message ID  : 36
Received message Sequence : 68
Received message ID  : 116
Received message Sequence : 71
Received message ID  : 29
Received message Sequence : 72
Received message ID  : 241
Received message Sequence : 102
Received message ID  : 74
Received message Sequence : 106
Received message ID  : 125
Received message Sequence : 115
Received message ID  : 42
Received message Sequence : 117
Received message ID  : 36
Received message Sequence : 118
Received message ID  : 29
Received message Sequence : 122
Received message ID  : 74
Received message Sequence : 156
Received message ID  : 42
Received message Sequence : 167
Received message ID  : 36
Received message Sequence : 168
Received message ID  : 125
Received message Sequence : 190
Received message ID  : 42
Received message Sequence : 192
Received message ID  : 36
Received message Sequence : 193
Received message ID  : 65
Received message Sequence : 194
Received message ID  : 74
Received message Sequence : 206
Received message ID  : 111
Received message Sequence : 213
Received message ID  : 125
Received message Sequence : 216
Received message ID  : 42
Received message Sequence : 218
Received message ID  : 36
Received message Sequence : 219
Received message ID  : 116
Received message Sequence : 222
Received message ID  : 125
Received message Sequence : 241
Received message ID  : 42
Received message Sequence : 243
Received message ID  : 36
Received message Sequence : 244
Received message ID  : 65
Received message Sequence : 245
Received message ID  : 241
Received message Sequence : 253
Received message ID  : 74
Received message Sequence : 1
Received message ID  : 42
Received message Sequence : 12
Received message ID  : 241
Received message Sequence : 49
Received message ID  : 42
Received message Sequence : 64
Received message ID  : 36
Received message Sequence : 65
Received message ID  : 125
Received message Sequence : 112
Received message ID  : 42
Received message Sequence : 114
Received message ID  : 36
Received message Sequence : 115
Received message ID  : 125
Received message Sequence : 137
Received message ID  : 125
Received message Sequence : 162
Received message ID  : 27
Received message Sequence : 192
Received message ID  : 116
Received message Sequence : 193
Received message ID  : 29
Received message Sequence : 194
Received message ID  : 241
Received message Sequence : 199
Received message ID  : 74
Received message Sequence : 203
Received message ID  : 125
Received message Sequence : 212
Received message ID  : 42
Received message Sequence : 214
Received message ID  : 36
Received message Sequence : 215
Received message ID  : 125
Received message Sequence : 237
Received message ID  : 42
Received message Sequence : 239
Received message ID  : 36
Received message Sequence : 240
Received message ID  : 65
Received message Sequence : 241
Received message ID  : 74
Received message Sequence : 253
Received message ID  : 125
Received message Sequence : 6
Received message ID  : 42
Received message Sequence : 8
Received message ID  : 36
Received message Sequence : 9
Received message ID  : 125
Received message Sequence : 31
Received message ID  : 42
Received message Sequence : 33
Received message ID  : 36
Received message Sequence : 34
Received message ID  : 65
Received message Sequence : 35
Received message ID  : 241
Received message Sequence : 43
Received message ID  : 74
Received message Sequence : 47

As you can see, the packet loss is severe(The message sequence does not increase by 1 and suddenly jumps, not linear)

[2] My code :

/* ~included for receiving serial char~ */
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <stdint.h>
#include <fcntl.h> //open()
#include <termios.h>
#include <errno.h>
#include <sys/ioctl.h>
/* ~inluded for receiving serial char~ */

#include "../include/mavlink/common/mavlink.h"
#include <iostream> //include for std::cout

int main(int argc, char *argv[])
{
int file_descriptor;
char c;
char buf[64] = "temp text";
struct termios toptions;

  /* open serial port */
file_descriptor = open("/dev/ttyUSB0", O_RDWR);
printf("file descriptor opened as %i\n", file_descriptor);

/* get current serial port settings to termios struct. */
tcgetattr(file_descriptor, &toptions);
/* set baud rate*/
cfsetispeed(&toptions, B57600);
cfsetospeed(&toptions, B57600);

/* 8 bits, no parity, 1 stop bits */
toptions.c_cflag &= ~PARENB;
toptions.c_cflag &= ~CSTOPB; /* only need 1 stop bit */
toptions.c_cflag &= ~CSIZE;
toptions.c_cflag |= CS8;

/* Enable Hardware flow control */
toptions.c_cflag |= CRTSCTS; /* enable hardware flow control */
toptions.c_iflag &= ~(IXON | IXOFF | IXANY);/* Disable software flow control */

/* Enable Software flow control */
//toptions.c_iflag |= (IXON | IXOFF | IXANY); /* Enable software flow control (XON/XOFF) */
//toptions.c_cflag &= ~CRTSCTS; /* no hardware flow control */

/* Disable both Hardware and Software Flow Control */
//toptions.c_cflag &= ~CRTSCTS; /* no hardware flow control */
//toptions.c_iflag &= ~(IXON | IXOFF | IXANY);/* Disable software flow control */

/* Canonical mode(for line-based input) */
// toptions.c_lflag |= ICANON; //canonical mode on
toptions.c_lflag &= ~ICANON; //canonical mode off

/* commit the serial port settings */
/* TCSANOW : the change shall occur immediately.
TCSADRAIN : the change shall occur after all output written to folders is transmitted.
this function should be used when changing parameters that affect output.
TCSAFLUSH : the change shall occur after all output written to folders is transmitted,
and all input so far received but not read shall be dsicarded before the change is made. */
tcsetattr(file_descriptor, TCSANOW, &toptions);

mavlink_status_t status;
mavlink_message_t msg;
int chan = MAVLINK_COMM_0;
uint8_t mavlink_byte;

while(true) {
int n = read(file_descriptor, &c, 1);

if(n > 0) {
mavlink_byte = static_cast<uint8_t>(c);
if(mavlink_parse_char(chan, mavlink_byte, &msg, &status)){
std::cout << "Received message ID  : " << static_cast<int>(msg.msgid) << std::endl;
std::cout << "Received message Sequence : " << static_cast<int>(msg.seq) << std::endl;
}
}
if(n < 1) {
perror("read");
break;
}
//add a small delay to reduce CPU usage <- don't use this. it will ruin the serial input result.
//usleep(10000); //10ms delay
}
close(file_descriptor);

return 0;
}//end of main()

[3] My Environment

  • Software: Latest ArduRover (2024.08)
  • Hardware: Jetson TK1 board (OS: Linux 4 Tegra 21.8, Jetpack 3.1)
  • Connection: Pixhawk 1 connected to Jetson TK1 via FT232

[4] What I’ve tried

I can successfully receive strings (e.g., “This is string”) from an Arduino Nano using the same code, suggesting no fundamental issue with the serial reception code.

I’ve also experimented with various serial port settings, but the result was same.

Additionally, I’ve tested the FT232 and Pixhawk connection with Windows Mission Planner, and it worked perfectly, so I believe the hardware setup is fine.

[5] Additional Question

When analyzing the raw serial data, I noticed that the “payload_length” field seems to be missing when the message ID type is VFR_HUD.

Is this normal, or could there be an issue with my serial communication?

The strange thing is, if I add the code below, MAVLink parsing suddenly stops working.

usleep(10000); //10ms delay

In Windows Mission Planner, the packet rate shows 100%, but on my Jetson TK1 board, I am experiencing close to 70% packet loss. It seems like MAVLink is very sensitive, and there might be an issue with the serial communication code on the Linux board.

I checked that the library is MAVLink v2, not MAVLink v1. The Pixhawk’s “SERIAL1_BAUD” is set to 57600, and the protocol is set to MAVLink v2.

Hi, I haven’t done this with a Jetson before but several times with a STM32 microcontroller which works fine.

I have never seen this, would suspect an issue with the serial communication.

Since you are only reading a single byte at a time the delay would quickly cause the receive buffers to fill up. At 57600bps you can expect a byte every 1/5760=173us.

Have you tried to slow the baud rate down and see if that improves things?
Maybe you can also try to read more bytes from the serial port at a time and then placing the parse function in a loop for each byte that was read?

[1] Hi, I haven’t done this with a Jetson before but several times with a STM32 microcontroller which works fine.
← Thank you for the response, but the STM32 is not a Linux OS-based system—it’s a completely different platform from the Jetson board. If you had experience with something like Raspberry Pi or LattePanda, it would be much more similar. I initially thought working with an OS-based system for receiving MAVLink messages or handling serial communication would be easier than on an MCU, but it’s turning out to be harder than expected (since I have to manipulate many many registers).

[2]
I have never seen this, would suspect an issue with the serial communication.

← Thank you very much. This information is helpful and exactly what I needed.
I appreciate your knowledge and experience.

[3]
Since you are only reading a single byte at a time the delay would quickly cause the receive buffers to fill up. At 57600bps you can expect a byte every 1/5760=173us.
Have you tried to slow the baud rate down and see if that improves things?

← After I uploaded the post, I already debugged the MAVLink receiving status variable, and it indicated a buffer overrun, so I’m aware of the issue. After making some changes to the serial register settings (which I’ll explain in a later post), the loss rate improved from 70% to “under 10%”. However, I still don’t understand why there’s a 10% loss rate, and I’m looking for a solution.

[4] Maybe you can also try to read more bytes from the serial port at a time and then placing the parse function in a loop for each byte that was read?

← The official MAVLink guide is giving the code parsing one byte at a time, but it doesn’t mention anything else. Serial communication over USB on a Linux embedded platform is not an easy task. I think the mavlink official guide should be updated and warn about this.

I believe I should be receiving one byte at a time, and adjusting the serial settings might be the key to solving the issue.

[Current Solution (Not Perfect)]

After analyzing the example code from the MAVLink official web page for receiving MAVLink messages using C on Unix-based systems, I adjusted the flags related to serial communication functions. This change reduced the loss rate from 70% to below 10%. However, I still don’t fully understand why this adjustment worked and there is still some data loss, so I am continuing to investigate.

The example code can be found here:

While simple serial communication examples on the internet work flawlessly with the Arduino Nano, handling MAVLink messages involves a much larger volume of data and more complex code. It requires additional configuration to ensure reliable communication.

I checked the loss rate using the code and found that it is still 27%. I previously mentioned that the loss rate was under 10%, but that was my mistake.

Here’s a working example:

Note the following changes:

/* ~included for receiving serial char~ */
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
#include <stdint.h>
#include <fcntl.h> //open()
#include <termios.h>
#include <errno.h>
#include <sys/ioctl.h>
/* ~inluded for receiving serial char~ */

//#include "../include/mavlink/common/mavlink.h"
#include <ardupilotmega/mavlink.h>
#include <iostream> //include for std::cout

int main(int argc, char *argv[])
{
    int file_descriptor;
    char c;
    char buf[64] = "temp text";
    struct termios toptions;

      /* open serial port */
    file_descriptor = open("/dev/ttyACM0", O_RDWR);
    printf("file descriptor opened as %i\n", file_descriptor);

    /* get current serial port settings to termios struct. */
    tcgetattr(file_descriptor, &toptions);
    /* set baud rate*/
    cfsetispeed(&toptions, B115200);
    //cfsetospeed(&toptions, B115200);

	// Input flags - Turn off input processing
	// convert break to null byte, no CR to NL translation,
	// no NL to CR translation, don't mark parity errors or breaks
	// no input parity check, don't strip high bit off,
	// no XON/XOFF software flow control
	toptions.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
						INLCR | PARMRK | INPCK | ISTRIP | IXON);

	// Output flags - Turn off output processing
	// no CR to NL translation, no NL to CR-NL translation,
	// no NL to CR translation, no column 0 CR suppression,
	// no Ctrl-D suppression, no fill characters, no case mapping,
	// no local output processing
	toptions.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
						 ONOCR | OFILL | OPOST);

	// No line processing:
	// echo off, echo newline off, canonical mode off,
	// extended input processing off, signal chars off
	toptions.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);

	// Turn off character processing
	// clear current char size mask, no parity checking,
	// no output processing, force 8 bit input
	toptions.c_cflag &= ~(CSIZE | PARENB);
	toptions.c_cflag |= CS8;

	// One input byte is enough to return from read()
	// Inter-character timer off
	toptions.c_cc[VMIN]  = 1;
	toptions.c_cc[VTIME] = 10; // was 0
	
    tcsetattr(file_descriptor, TCSANOW, &toptions);

    mavlink_status_t status;
    mavlink_message_t msg;
    int chan = MAVLINK_COMM_0;
    uint8_t mavlink_byte;

    while(true) {
        int n = read(file_descriptor, &c, 1);

        if(n > 0) {
            mavlink_byte = static_cast<uint8_t>(c);
            if(mavlink_parse_char(chan, mavlink_byte, &msg, &status)){
                std::cout << "Received message ID  : " << static_cast<int>(msg.msgid) << std::endl;
                std::cout << "Received message Sequence : " << static_cast<int>(msg.seq) << std::endl;
            }
        }
        else {
            usleep(1); //1us delay
        }
    }
    close(file_descriptor);

    return 0;
}//end of main()

Oh, you are a savior. You rescued me from a mysterious error. Thank you🙏

Before you mentioned it, I had already referred to the source codes from the GitHub page linked in the MAVLink guide and adjusted the serial setup accordingly. However, I still couldn’t figure out why the message loss rate remained at 27%.

The issue turned out to be that I needed to use the “ardupilotmega” dialect instead of “common.”

The official MAVLink guide suggests using “common,” but it’s an guide that overlooks ArduPilot. I hope they add an explanation about this for beginner developers on their website.

Still, I’ve learned something: when using the “common” dialect instead of “ardupilotmega” on ArduRover, the message loss rate is approximately 27%.

it’s not a message loss rate but the number of packets that it can parse, by setting it to Ardupilot, it now understands all of them. I would get a similar issue with out-of-date Mavlink libraries.

2 Likes

Yes, I understand what you’re saying and what code does. Sorry for my poor English, I chose the wrong phrase.

1 Like