MAVLink: Are the Two Telemetry Ports on Pixhawk Not Independent?

Hello,

I’m unsure whether this is a bug or if it’s an issue on my code, so I’d like to get confirmation from experts here.

Thank you in advance. :pray:

I’ve uploaded my “ReadArduRoverModeSimple” code below:

[Code]

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

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

std::string arduRoverModeNumberToString(uint32_t custom_mode)
{
    switch(custom_mode)
      {
    case 0 : return "MANUAL";
    case 1 : return "ACRO";
    case 3 : return "STEERING";
    case 4 : return "HOLD";
    case 5 : return "LOITER";
    case 6 : return "FOLLOW";
    case 7 : return "SIMPLE";
    case 10 : return "AUTO";
    case 11 : return "RTL";
    case 12 : return "SMART_RTL";
    case 15 : return "GUIDED";
    case 16 : return "INITIALIZING";
    default : return "UNKNOWN";
    }
}

int main(int argc, char *argv[])
{
    int file_descriptor;
    struct termios toptions;
    
    //file_descriptor = open("/dev/ttyUSB0" , O_RDWR | O_NOCTTY | O_NDELAY); <- have error. but official "uart-c" example code use this setup
    file_descriptor = open("/dev/ttyUSB0" , O_RDWR | O_NOCTTY);
    std::cout << "file descriptor opened as int : " << file_descriptor << std::endl;
    
    tcgetattr(file_descriptor, &toptions);
    
    cfsetispeed(&toptions, B57600);
    cfsetospeed(&toptions, B57600);
    
    /* 8 bits, no parity, no stop bits */
    toptions.c_cflag &= ~(CSIZE | PARENB);
    toptions.c_cflag |= CS8;
    
    //Mavlink official "uart-c" example code use this input flag.
    toptions.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON);
    
    //Mavlink official "uart-c" example code use this local flag.
    toptions.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
    
    toptions.c_cc[VTIME] = 1;
    toptions.c_cc[VMIN] = 10;
    
    /* commit the serial port settings */
    tcsetattr(file_descriptor, TCSANOW, &toptions);
    //tcsetattr(file_descriptor, TCSAFLUSH, &toptions);
    
    mavlink_status_t status;
    mavlink_message_t msg;
    int chan = MAVLINK_COMM_0;
    uint8_t mavlink_byte;
    int last_msg_sequence = 0;
    int lost_message_number = 0;
    
    while(true) {
        //read(int fd, void *buf, size_t count);
        int number = read(file_descriptor, &mavlink_byte, 1);
        if(number > 0)
        {
            if(mavlink_parse_char(chan, mavlink_byte, &msg, &status))
            {
              if(msg.msgid == MAVLINK_MSG_ID_HEARTBEAT)
              {
              mavlink_heartbeat_t heartbeat;
              mavlink_msg_heartbeat_decode(&msg, &heartbeat);
              std::cout << "ArduRover Mode : " << arduRoverModeNumberToString(heartbeat.custom_mode) << std::endl;
               }
              
              //Counting lost-message algorithm
              if(last_msg_sequence > msg.seq)
              {
              std::cout << "Lost Message Number : " << lost_message_number << std::endl;
              std::cout << "Lost Percentage : " << (float)((float)lost_message_number / 255) * 100 << std::endl;
              lost_message_number = 0;
              lost_message_number += (msg.seq);
              }
              else if((msg.seq - last_msg_sequence) != 1)
              {
              lost_message_number += (msg.seq - last_msg_sequence - 1);
              }
              last_msg_sequence = msg.seq;
              }
        }
        else if(number < 1) {
              std::cout << "Serial Getting Failed." << std::endl;
              break;
        }
        else //number = 0
        {
              std::cout << "no serial data" << std::endl;
        }
    }//end of while(true)
    close(file_descriptor);
    
    return 0;
}//end of main()

The expected result should be a continuous “GUIDED” output when I switch the transmitter to “GUIDED.”

Below is the terminal output when I connect the Jetson TK1 and Pixhawk:

[Terminal Result 1]

file descriptor opened as int : 3
ArduRover Mode : HOLD
ArduRover Mode : HOLD
ArduRover Mode : HOLD
ArduRover Mode : HOLD
ArduRover Mode : MANUAL
ArduRover Mode : MANUAL
Lost Message Number : -526
Lost Percentage : -206.275
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
Lost Message Number : 0
Lost Percentage : 0
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
ArduRover Mode : GUIDED
Lost Message Number : 0
Lost Percentage : 0
ArduRover Mode : GUIDED

As you can see above, the lost message count is zero, and the “GUIDED” mode is correctly reported.

However, when connecting a SiK Radio telemetry module and running Windows Mission Planner simultaneously on a Windows laptop(independently with Jetson TK1), I get the following result on the console:

[Terminal Result 2(Failed)]

file descriptor opened as int : 3
ArduRover Mode : MANUAL
Lost Message Number : -16
Lost Percentage : -6.27451
Lost Message Number : 247
Lost Percentage : 96.8627
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 22
Lost Percentage : 8.62745
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 44
Lost Percentage : 17.2549
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 95
Lost Percentage : 37.2549
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 147
Lost Percentage : 57.6471
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 199
Lost Percentage : 78.0392
Lost Message Number : 253
Lost Percentage : 99.2157
ArduRover Mode : GUIDED
Lost Message Number : 36
Lost Percentage : 14.1176
ArduRover Mode : MANUAL
Lost Message Number : 56
Lost Percentage : 21.9608
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 51
Lost Percentage : 20
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 102
Lost Percentage : 40
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 154
Lost Percentage : 60.3922
ArduRover Mode : GUIDED
Lost Message Number : 206
Lost Percentage : 80.7843
ArduRover Mode : MANUAL
Lost Message Number : 73
Lost Percentage : 28.6275
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 25
Lost Percentage : 9.80392
ArduRover Mode : GUIDED
ArduRover Mode : MANUAL
Lost Message Number : 55
Lost Percentage : 21.5686

There are sudden message losses, and the mode switches between “GUIDED” and “MANUAL” even though I haven’t touched the transmitter. Meanwhile, Mission Planner still shows the flight mode as “GUIDED” continuosly.

As a beginner with MAVLink and Linux boards, I can’t figure out why this is happening. If anyone has insights into this issue, I would greatly appreciate any suggestions or explanations.

I think connecting the radio telemetry module in addition to the FT232 module to the Pixhawk does not affect the telemetry output on the FT232 module, but it seems to have some impact. Aren’t the two telemetry ports independent? Could this issue be related to the Pixhawk code or hardware, or should I modify my code to address potential problems?

[My Environment]

  • Software: Latest ArduRover (2024.08)
  • Hardware: Jetson TK1 board (OS: Linux 4 Tegra 21.8, Jetpack 3.1), Quite old
  • Connection: ArduRovers’s Pixhawk 1 connected to Jetson TK1 via FT232, and connected to windows laptop with SiK Radio Telemetry.

now that you mention it I have been having a similar problem when reading flight modes from my controller using fcmodein = (hb.custom_mode) it jumps between the mode number and 0 (manual mode). I just thought I was doing something wrong but i couldn’t work out where the 0 was coming from.

with mavlink all packets are routed to all mavlink ports, is it picking it up from the ground station instead of the flight controller?

1 Like

You’ve described my problem exactly.

After I connect Mission Planner in addition to the existing Jetson TK1 board connection, the flight mode data jumps from 0 (manual mode) to the intended flight mode whenever I set it to guided mode.

The two telemetry ports are independent, so they shouldn’t affect each other, but it seems like they do.

If Mavlink routing is the issue, Mission Planner should also show the mode switching, but it still stays in “guided” mode.

I’ll try changing the GCS ID tomorrow. Could it be a GCS ID conflict?

im not sure. I never found the cause, I have a lot of mavlink devices so I wasnt use what one was the issue. so i just put it on the list of things i need to look at.

I found the following factors:

[Mission Planner]
The “GCS ID” in the “Config-Planner” section allows you to specify its GCS ID:

[ArduRover]
The “SYSID_MYGCS” parameter in the “Full Parameter List”:


These settings are intended to prevent interference from other GCSs and to control communication with a specific group of GCSs. They are not designed for distinguishing between multiple GCSs in a multi-GCS setup. usually, ,all GCSs can use the “255” ID without issues.

I changed these parameters from 255 to 250, but it did not resolve the problem.

Interestingly, changing this ID does not seem to affect my Jetson TK1’s ability to read data from the Pixhawks. It might only impact writing abilities.

I think I’m getting closer to the solution.

I printed the “type” attribute from the heartbeat message.

  • When both base_mode and custom_mode are 0, the heartbeat type is “6” (MAV_TYPE_GCS).
  • When it correctly prints ArduRover’s mode, the heartbeat message type is “10” (MAV_TYPE_GROUND_ROVER).

[Result]
When you connect the Telem1 port to Windows Mission Planner in addition to the Telem2 port serial connection to the Jetson TK1 board, incoming messages from the Telem1 port will also be output to the Telem2 port. This indicates that the two telemetry ports are not independent.

Thank you for the hint about “routing.”

In the Ardupilot serial port options there is an option for “Dont forward mavlink to/from” you could try that with the port that the jetson is on.

1 Like

I now understand why some gimbal cameras use the MAVLink protocol.

I previously thought that the GCS didn’t directly control them, and that when the GCS sent a MAVLink signal to the flight controller (FC), the FC would generate a separate MAVLink message to the gimbal camera. However, it turns out the GCS can directly control the gimbal camera.

It seems I need to study the MAVLink documentation from the basics.

Thank you very much.

yes, I have a Mavlink lidar and I can get a much higher resolution display if I get the data direct from the lidar rather than the proximity view the flight controller gives.

1 Like

ok I figured out where my problem was, I had some other Mavlink devices also set as type 10 Rover instead of something like MAV_TYPE_ONBOARD_CONTROLLER type 18, so i was picking up modes from all the heartbeats.

I also added

if (hb.type == 10) {
fcmodein = (hb.custom_mode);

so it only gets the flight mode from a type 10 device now.

2 Likes

Hello,

Since I had already solved this issue, I didn’t think much of it initially after reading your post, but today I realized that you’re filtering messages based on the heartbeat, and I wanted to ask about that.

In the C++ library, the message object has the following attributes:

uint16_t checksum;
uint8_t magic;           // Protocol magic marker
uint8_t len;             // Payload length
uint8_t incompat_flags;  // Flags that must be understood
uint88_t compat_flags;    // Flags that can be ignored if not understood
uint8_t seq;             // Packet sequence
uint8_t sysid;           // System/aircraft ID of the message sender
uint8_t compid;          // Component ID of the message sender
uint32_t msgid:24;       // Message ID in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_CHECKSUM_BYTES + 7) / 8];
uint8_t ck[2];           // Checksum bytes
uint88_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];

If you’re only filtering by the heartbeat, other messages from a different GCS (e.g., Windows Mission Planner) will still be received by the current GCS. It seems that distinguishing messages by sysid might be a more reliable approach. Could I ask which library and programming language you’re using? The object structure might differ depending on the library or language.

Today, I ran some experiments, but unexpectedly, MAVLink routing stopped working. Interestingly, both the Mission Planner and Jetson TK1 are functioning well on their own, but they aren’t receiving messages from each other. I’m not sure what’s causing this strange behavior—the code seems to behave unpredictably without clear rules.