MAVLink and Arduino: step by step

yes!thank you so much

dear Dennisw6, in the above line, you did’t set the message you want to receive to RC channel data.am I right?

Hi Zara,

Thanks on your quick answer! I am not pretty sure which values I should use. I am a bit confused about system and component id in general. I understood that I have to use 1 for both system and component id since it means that we are receiving messages from Pixhawk, and that is the reason why I put these values here.

Kind regards,
Djordje

as mentioned in “mavlink_msg_request_data_stream.h”,

/**

  • @brief Pack a request_data_stream message
  • @param system_id ID of this system
  • @param component_id ID of this component (e.g. 200 for IMU)
  • @param msg The MAVLink message to compress the data into
  • @param target_system The target requested to send the message stream.
  • @param target_component The target requested to send the message stream.
  • @param req_stream_id The ID of the requested data stream
  • @param req_message_rate [Hz] The requested message rate
  • @param start_stop 1 to start sending, 0 to stop sending.
  • @return length of the message in bytes (excluding serial stream start sign)
    /
    static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t
    msg,
    uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
    {

    this means that the system id is the id of the vehicle (which can be set 1). But when you set component ID to 1, it means that “I am pixhawk”. So, this leads to conflict with the data of pixhawk and your message will be ignored. (These are all my own experiences and may be incorrect. Try it for your case)
    all the header files contain descriptions which can help you understand the params.
    best wishes
    I hope this helps you.
1 Like

Hi Zara,

Thanks on your reply! Yes, I understand that, but I cannot figure out which values should I use as component id. In my case, I have to make communication between Pixhawk and Arduino, so I have to use values which are correlated with these two components. Am I wright or not? Do you suggest any values for component id?

Thanks in advance!

Kind regards,
Djordje

Hi Djordje, sorry for being late!
I set the component ID to 191 and it worked for me! I hope it works for you, too.
Best regards
zara

@jplopezll
Dear Pedro,
thank you for your very complete and useful tutorial, I uploaded your code( with a bit change) on my arduino mega as below,
#include <mavlink.h>
#include <SoftwareSerial.h>

// Mavlink variables
unsigned long previousMillisMAVLink = 0; // will store last time MAVLink was transmitted and listened
unsigned long next_interval_MAVLink = 1000; // next interval to count
const int num_hbs = 60; // # of heartbeats to wait before activating STREAMS from Pixhawk. 60 = one minute.
int num_hbs_pasados = num_hbs;

void setup()
{
// MAVLink interface start
Serial1.begin(57600);

Serial.begin(57600);
Serial.println(“MAVLink starting.”);
}

void loop()
{

// MAVLink
/* The default UART header for your MCU */
int sysid = 1; ///< ID 20 for this airplane. 1 PX, 255 ground station
int compid = 191; ///< The component sending the message
int type = MAV_TYPE_QUADROTOR; ///< This system is an airplane / fixed wing

// Define the system type, in this case an airplane → on-board controller
// uint8_t system_type = MAV_TYPE_FIXED_WING;
uint8_t system_type = MAV_TYPE_GENERIC;
uint8_t autopilot_type = MAV_AUTOPILOT_INVALID;

uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up
uint32_t custom_mode = 0; ///< Custom mode, can be defined by user/adopter
uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight

// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// Pack the message
mavlink_msg_heartbeat_pack(sysid, compid, &msg, type, autopilot_type, system_mode, custom_mode, system_state);

// Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

// Send the message with the standard UART send function
// uart0_send might be named differently depending on
// the individual microcontroller / library in use.
unsigned long currentMillisMAVLink = millis();
if (currentMillisMAVLink - previousMillisMAVLink >= next_interval_MAVLink)
{
// Record last HB update
previousMillisMAVLink = currentMillisMAVLink;

Serial1.write(buf, len);
//Mav_Request_Data();
num_hbs_pasados++;
if (num_hbs_pasados >= num_hbs)
{
  // Request streams from Pixhawk
  Serial.println("Streams requested!");
  Mav_Request_Data();
  num_hbs_pasados = 0;
}

}

// Check reception buffer
comm_receive();

}

void Mav_Request_Data()
{
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// To be setup according to the needed information to be requested from the Pixhawk
const int maxStreams = 2;
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_EXTENDED_STATUS, MAV_DATA_STREAM_EXTRA1};
const uint16_t MAVRates[maxStreams] = {0x02, 0x05};

for (int i = 0; i < maxStreams; i++) {

mavlink_msg_request_data_stream_pack(1, 191, &msg, 1, 0, MAVStreams[i], MAVRates[i], 1);
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
Serial1.write(buf, len);

}
}

void comm_receive() {
mavlink_message_t msg;
mavlink_status_t status;

while (Serial1.available() > 0) {
uint8_t c = Serial1.read();

// Try to get a new message
if (mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
{
  Serial.print("DEBUG msgid:");
  Serial.println(msg.msgid);

  // Handle message
  switch (msg.msgid) {
    case MAVLINK_MSG_ID_HEARTBEAT:  // #0: Heartbeat
      {
        // E.g. read GCS heartbeat and go into
        // comm lost mode if timer times out
        
        Serial.println("PX HB");

      }
      break;

    case MAVLINK_MSG_ID_SYS_STATUS:  // #1: SYS_STATUS
      {
        /* Message decoding: PRIMITIVE
              mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
        */
        //mavlink_message_t* msg;
        mavlink_sys_status_t sys_status;
        mavlink_msg_sys_status_decode(&msg, &sys_status);

        Serial.print("PX SYS STATUS: ");
        Serial.print("[Bat (V): ");
        Serial.print(sys_status.voltage_battery);
        Serial.print("], [Bat (A): ");
        Serial.print(sys_status.current_battery);
        Serial.print("], [Comms loss (%): ");
        Serial.print(sys_status.drop_rate_comm);
        Serial.println("]");

      }
      break;

    case MAVLINK_MSG_ID_PARAM_VALUE:  // #22: PARAM_VALUE
      {
        /* Message decoding: PRIMITIVE
              mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
        */
        //mavlink_message_t* msg;
        mavlink_param_value_t param_value;
        mavlink_msg_param_value_decode(&msg, &param_value);

        Serial.println("PX PARAM_VALUE");
        Serial.println(param_value.param_value);
        Serial.println(param_value.param_count);
        Serial.println(param_value.param_index);
        Serial.println(param_value.param_id);
        Serial.println(param_value.param_type);
        Serial.println("------ Fin -------");

      }
      break;

    case MAVLINK_MSG_ID_RAW_IMU:  // #27: RAW_IMU
      {
        /* Message decoding: PRIMITIVE
              static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
        */
        mavlink_raw_imu_t raw_imu;
        mavlink_msg_raw_imu_decode(&msg, &raw_imu);

        Serial.println("PX RAW IMU");
        Serial.println(raw_imu.xacc);

      }
      break;

    case MAVLINK_MSG_ID_ATTITUDE:  // #30
      {
        /* Message decoding: PRIMITIVE
              mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
        */
        mavlink_attitude_t attitude;
        mavlink_msg_attitude_decode(&msg, &attitude);
        Serial.println("PX ATTITUDE");
        Serial.println(attitude.roll);

      }
      break;


    default:

      Serial.print("--- Others: ");
      Serial.print("[ID: ");
      Serial.print(msg.msgid);
      Serial.print("], [seq: ");
      Serial.print(msg.seq);
      Serial.println("]");

      break;
  }
}

}
}
But I receive just message #66, which is REQUEST_DATA_STREAM.
what is my mistake?please help me

Hi @Djordje_Jevtic ,
My autopilot, a Cube Orange, is SysID 1, CompID 1.
So I make my Arduino SysID 1 and CompID 100.
I set the Arduino SysID to 1 because the SysID of any MAVLink device that is in your drone should match the AutoPilot susID.
I set the Arduino CompID to 100 because you can pick any number between 2-254 as best I can tell. You just need to make sure it is not the same as any other MAVLink device in your drone.
Does that make sense?

Also I have put together a full MAVLink Tester and placed it on GitHub here GitHub - pauljeffress/Pulsar-MAVLink-Tester

That should help you a lot.
Cheers,
Paul

You are correctly using 1, 191 for your Arduino’s sysID, compID
You are using the correct sysID for your AutoPilot of 1 BUT you are using compID 0 and that should be 1.
So your code should be…
mavlink_msg_request_data_stream_pack(1, 191, &msg, 1, 1, MAVStreams[i], MAVRates[i], 1);

Hello
I dont know if this is the correct place to post but here goes. Perhaps someone here may direct me.
I wrote a serial communication program (in delphi programming language) I used the MAVLink unit to try and communicate with devices using the Mavlink protocol. I do know that the pixhawk, CC3D Revolution and most flight controller boards use the MAVlink protocol for telemetry communication.
I just cant read any data from any flight controller. You can assist here?

Hi, @techdesk:

I am not familiar with delphi, but it looks more like a wiring issue. When MAVLink is activated, it should send heartbeats to inform that somebody is there…

If you are sure that your wiring is correct, then it might be that the library is not properly configured or that you are mixing versions 1 and 2 of the protocol.

KR

Hey @jplopezll
I’m trying to send the GPS latitude, longitude, and altitude from the TELEM 2 port on the Pixhawk to the Serial1 port on an Arduino Mega. I have tried the code below but all I keep getting is: 11:32:39.791 → ��f����������~��~����~��怘�f~fxf��fxf~f��~fx���MAVLink starting.
11:32:41.699 → Streams requested!. Then I get “Streams requested!” every 60 seconds with no other output. I have already configured the baud rate to 57600 and the protocol to Mavlink1 in Mission Planner. Do you have any theories on what might be the problem?

#include <C:\Users\ibraa\Documents\Arduino\mavlink\mavlink.h>
#include <SoftwareSerial.h>

// Mavlink variables
unsigned long previousMillisMAVLink = 0; // will store last time MAVLink was transmitted and listened
unsigned long next_interval_MAVLink = 1000; // next interval to count
const int num_hbs = 60; // # of heartbeats to wait before activating STREAMS from Pixhawk. 60 = one minute.
int num_hbs_pasados = num_hbs;

void setup()
{
// MAVLink interface start
Serial1.begin(57600);

Serial.begin(57600);
Serial.println("MAVLink starting.");
}

void loop()
{

// MAVLink
/* The default UART header for your MCU */
int sysid = 1; ///< ID 20 for this airplane. 1 PX, 255 ground station
int compid = 191; ///< The component sending the message
int type = MAV_TYPE_QUADROTOR; ///< This system is an airplane / fixed wing

// Define the system type, in this case an airplane → on-board controller
// uint8_t system_type = MAV_TYPE_FIXED_WING;
uint8_t system_type = MAV_TYPE_GENERIC;
uint8_t autopilot_type = MAV_AUTOPILOT_INVALID;

uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up
uint32_t custom_mode = 0; ///< Custom mode, can be defined by user/adopter
uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight

// Initialize the required buffers
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// Pack the message
mavlink_msg_heartbeat_pack(sysid, compid, &msg, type, autopilot_type, system_mode, custom_mode, system_state);

// Copy the message to the send buffer
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);

// Send the message with the standard UART send function
// uart0_send might be named differently depending on
// the individual microcontroller / library in use.
unsigned long currentMillisMAVLink = millis();
if (currentMillisMAVLink - previousMillisMAVLink >= next_interval_MAVLink)
{
// Record last HB update
previousMillisMAVLink = currentMillisMAVLink;

Serial1.write(buf, len);
//Mav_Request_Data();
num_hbs_pasados++;
if (num_hbs_pasados >= num_hbs)
{
  // Request streams from Pixhawk
  Serial.println("Streams requested!");
  Mav_Request_Data();
  num_hbs_pasados = 0;
}
}

// Check reception buffer
comm_receive();

}

void Mav_Request_Data()
{
  // STREAMS that can be requested
  /*
   * Definitions are in common.h: enum MAV_DATA_STREAM and more importantly at:
     https://mavlink.io/en/messages/common.html#MAV_DATA_STREAM
   *   
   * MAV_DATA_STREAM_ALL=0, // Enable all data streams
   * MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
   * MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
   * MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
   * MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
   * MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
   * MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot
   * MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot
   * MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot
   * MAV_DATA_STREAM_ENUM_END=13,
   * 
   * Data in PixHawk available in:
   *  - Battery, amperage and voltage (SYS_STATUS) in MAV_DATA_STREAM_EXTENDED_STATUS
   *  - Gyro info (IMU_SCALED) in MAV_DATA_STREAM_EXTRA1
   */
mavlink_message_t msg;
uint8_t buf[MAVLINK_MAX_PACKET_LEN];

// To be setup according to the needed information to be requested from the Pixhawk
const int maxStreams = 1;
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_RAW_SENSORS};
const uint16_t MAVRates[maxStreams] = {0x02};

for (int i = 0; i < maxStreams; i++) {

mavlink_msg_request_data_stream_pack(1, 191, &msg, 1, 1, MAVStreams[i], MAVRates[i], 1);
uint16_t len = mavlink_msg_to_send_buffer(buf, &msg);
Serial1.write(buf, len);
}
}

void comm_receive()  { 
  mavlink_message_t msg;
  mavlink_status_t status;
 
  while(Serial1.available())
  {
    uint8_t c= Serial1.read();
 
    //Get new message
    if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status))
    {
 
    //Handle new message from autopilot
      switch(msg.msgid)
      {
 
        case MAVLINK_MSG_ID_GPS_RAW_INT:
      {
        mavlink_gps_raw_int_t packet;
        mavlink_msg_gps_raw_int_decode(&msg, &packet);
        
        Serial.print("\nGPS Fix: ");Serial.println(packet.fix_type);
        Serial.print("GPS Latitude: ");Serial.println(packet.lat);
        Serial.print("GPS Longitude: ");Serial.println(packet.lon);
        Serial.print("GPS Speed: ");Serial.println(packet.vel);
        Serial.print("Sats Visible: ");Serial.println(packet.satellites_visible);
       
      }
      break;
 
      }
    }
  }
}

Hi, @Ibrahim_Alzoubi:

It also looks like a wiring issue. To be sure, please post wiring diagram.

KR

Can we please meet in a Zoom meeting please?

Hi, @Ibrahim_Alzoubi:

Sorry, but I do not attend that kind of requests. If you need to contact with me, this is the right place. If you want someting more private, you can send me a PM.

KR

Ok, here is my wiring diagram:

Will I need to be connected or disconnected from MissionPlanner when I run the program? Is the code I posted even correct?

Hi, @Ibrahim_Alzoubi:

You don’t need Mission Plan er for MAVLink ro be active.

I can see you connected the 5 V. What for? For the communications to work you only need TX, RX and GND.

Powering of both the Pixhawk and the Mega should be done by other means.

KR

Ok, I have the powered the Pixhawk from a battery and the Mega is powered from the computer. The only connections between the Pixhawk and Mega is GND, TX1, and RX1. I am still getting the same result. Could it be the way I’m trying to request the raw GPS data packet or how my code is unpacking it? A theory could be an error with the comm_receive() function?

Hi, I suspect your issue is either a serial port speed mismatch between you autopilot and arduino or a voltage level issue. Are both devices 5v serial ports or is one 3.3v?

Actually that output you are showing that looks like
��f����������~��~����~��怘�f~fxf��fxf~f��~fx��
Where exactly is that being printed from in your code.
I haven’t messed with this stuff in a while but MAVLink is a binary protocol, so if you “printed” it it will look like gibberish.
What I like to do is print msg.id just above your switch statement. That way you can at least see what MAVLink packet your arduino has received before anything else. That’s a really good first step.