Using MAVLink for custom applications.

Tony Jacob
6 min readJun 15, 2023

--

The MAVLink (Micro Air Vehicle Link) protocol is a well established communication protocol mainly used between drones and GCS’s (Ground Control Stations). It comprises of a large set of messages that can be utilized for communication of very specific information. It bears the advantage of having an implementation for checksum and data integrity by default. In addition, its agnostic nature towards the underlying technology it is being deployed on (WiFi, RF etc) makes the protocol a stellar candidate for serial communication across devices.

The majority of the documented implementation of MAVLink involves ArduPilot or PX4 drones and its corresponding communication with some GCS software.

However with this blog, I want to bring to light the knowledge on how to use this protocol for any custom applications. For further reading, this paper is a well documented starter to better understand the nitty-grittys of MAVLink.

PyMAVLink

The protocol is designed in such a way that it is agnostic to the mode of communication. In the same spirit, it also has wrappers for multiple languages for its utilization. The python wrapper for the same is PyMAVLink which is what will be the focus of this blog.

pip install pymavlink

It is also important that sometimes it is better to build MAVLink from source, for the implementation of the custom messages. One can follow the guide for the same here.

As mentioned, the protocol is physical layer agnostic. Hence, one can use it across any technology that uses serial communication. This particular blog is scoped out for a UDP port on the localhost and through RF.

The radio modules I had used for this project.
#Script to transmit via MAVLink (Drone Side)
from pymavlink import mavutil

#If through WiFi
mavlink_connection = mavutil.mavlink_connection(device='udpout:127.0.0.1:14550', baudrate=57600)
#Else through a radio antenna,
mavlink_connection = mavutil.mavserial(device='/dev/ttyUSB1', baud=57600)

The only change required to use between RF and UDP would be in connection string and the method. If using an RF module with USB, use the mavserial class along with the serial port in which the module is connected with the computer at baud rate 57600.

On the UDP side of things, the key takeaway here is to use “udpout” (think of it as spewing out data) as the protocol for the vehicle side. Similarly for the reception, the protocol is “udpin”. Note to keep the baud rate & the [ip:port] same between the drone side and GCS side.

#Script to receive via MAVLink (GCS side)
from pymavlink import mavutil

#If through WiFi
mavlink_connection = mavutil.mavlink_connection(device='udpin:127.0.0.1:14550', baudrate=57600)

#Else through a radio antenna,
mavlink_connection = mavutil.mavserial(device='/dev/ttyUSB0', baud=57600)

More protocols and variations of the connection string can be found here.

Heartbeat

One of the primary characteristic of this protocol is the transmission of the heartbeat message. It is essential for system identification, status monitoring, and coordination between MAVLink systems. It also serves as a starting point for MAVLink communication. Other systems can detect the presence of a MAVLink-enabled system and establish communication by monitoring the receipt of heartbeat messages.

https://ardupilot.org/dev/docs/mavlink-basics.html

Therefore, the heartbeat message is essential to initiate a conversation between the drone and the GCS. Typically, the drone side sends out a heartbeat and the GCS sounds receives it. On reception, it will get more information about the vehicle and then the communication bridge is set.

#Script to transmit via MAVLink (Drone Side)
while True:
mavlink_connection.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
mavutil.mavlink.MAV_AUTOPILOT_INVALID, 0, 0, 0)

The GCS side uses a blocking function to receive the heartbeat initiated by the drone. Until the heartbeat is received, the rest of the script doesn’t get executed.

#Script to receive via MAVLink (GCS side)
mavlink_connection.wait_heartbeat()

More on heartbeat can be found here.

Sending and Receiving Messages.

MAVLink messages are standardized and has its own measures to guarantee reliability of messages. Therefore it is important to use the messages in its intended fashion, subjected to data types and information as it requires.

For example, to send an ATTITUDE message,

mavlink_connection.mav.attitude_send(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)
"""
The attitude in the aeronautical frame (right-handed, Z-down, Y-right,
X-front, ZYX, intrinsic).

time_boot_ms : Timestamp (time since system boot). [ms] (type:uint32_t)
roll : Roll angle (-pi..+pi) [rad] (type:float)
pitch : Pitch angle (-pi..+pi) [rad] (type:float)
yaw : Yaw angle (-pi..+pi) [rad] (type:float)
rollspeed : Roll angular speed [rad/s] (type:float)
pitchspeed : Pitch angular speed [rad/s] (type:float)
yawspeed : Yaw angular speed [rad/s] (type:float)

"""

One can fill this message structure abiding by its data type constraints. The wrapper encodes this messages and sends it across the transport layer through the MAVLink protocol.

Similarly to send a GPS message, use the pre-defined message structure and fill in necessary information.

  mavlink_connection.mav.gps_input_send(    
0, # Timestamp (micros since boot or Unix epoch)
0, # ID of the GPS for multiple GPS inputs
# Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum).
# All other fields must be provided.
8 | 16 | 32,
0, # GPS time (milliseconds from start of GPS week)
0, # GPS week number
3, # 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
latitude, # Latitude (WGS84), in degrees * 1E7
longitude, # Longitude (WGS84), in degrees * 1E7
depth, # Altitude (AMSL, not WGS84), in m (positive for up)
1, # GPS HDOP horizontal dilution of position in m
1, # GPS VDOP vertical dilution of position in m
0, # GPS velocity in m/s in NORTH direction in earth-fixed NED frame
0, # GPS velocity in m/s in EAST direction in earth-fixed NED frame
0, # GPS velocity in m/s in DOWN direction in earth-fixed NED frame
0, # GPS speed accuracy in m/s
0, # GPS horizontal accuracy in m
0, # GPS vertical accuracy in m
0 # Number of satellites visible
)

For other type of MAVLink messages, one is recommended to go through the generated_messages.py (from line 12667) that gets generated from mavgen.py

Once the heartbeat is received by the GCS, it now knows the system it is receiving information from. PyMAVLink uses recv_msg() function to grab MAVLink messages.

#Script to receive via MAVLink (GCS side)
msg = mavlink_connection.recv_msg()

Alternatively, one can use recv_match() to filter just messages of choosing by passing in the type of message one desires. For example,

#Script to receive via MAVLink (GCS side)
msg = mavlink_connection.recv_match(type = 'ATTITUDE')

The above code block, would now only receive ATTITUDE messages. Once can even fine tune the type of messages you want to receive. More on that, here.

The complete code

Vehicle side. This sends the vehicle’s GPS coordinates at (41, -71)

#Script to transmit via MAVLink (Drone Side)
from pymavlink import mavutil
import time

#If through WiFi
mavlink_connection = mavutil.mavlink_connection(device='udpout:192.168.1.163:14551', baudrate=57600)

while True:
mavlink_connection.mav.heartbeat_send(mavutil.mavlink.MAV_TYPE_ONBOARD_CONTROLLER,
mavutil.mavlink.MAV_AUTOPILOT_INVALID, 0, 0, 0)
print("[INFO]Heartbeat sent")

mavlink_connection.mav.gps_input_send(
0, # Timestamp (micros since boot or Unix epoch)
0, # ID of the GPS for multiple GPS inputs
# Flags indicating which fields to ignore (see GPS_INPUT_IGNORE_FLAGS enum).
# All other fields must be provided.
8 | 16 | 32,
0, # GPS time (milliseconds from start of GPS week)
0, # GPS week number
3, # 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
41, # Latitude (WGS84), in degrees * 1E7
-71, # Longitude (WGS84), in degrees * 1E7
10, # Altitude (AMSL, not WGS84), in m (positive for up)
1, # GPS HDOP horizontal dilution of position in m
1, # GPS VDOP vertical dilution of position in m
0, # GPS velocity in m/s in NORTH direction in earth-fixed NED frame
0, # GPS velocity in m/s in EAST direction in earth-fixed NED frame
0, # GPS velocity in m/s in DOWN direction in earth-fixed NED frame
0, # GPS speed accuracy in m/s
0, # GPS horizontal accuracy in m
0, # GPS vertical accuracy in m
0 # Number of satellites visible
)

#Sleep for 1 second
time.sleep(1)

Ground Control Station side. Simply receives all the messages and prints it.

#Script to receive via MAVLink (GCS side)
from pymavlink import mavutil

#If through WiFi
mavlink_connection = mavutil.mavlink_connection(device='udpin:192.168.1.163:14551', baudrate=57600)

#Else through a radio antenna,
# mavlink_connection = mavutil.mavserial(device='/dev/ttyUSB0', baud=57600)

while 1:
mavlink_connection.wait_heartbeat()
print("[INFO] Heartbeat Received")
msg = mavlink_connection.recv_msg()
print(msg)

Conclusion

I wanted to aggregate all the information I found on how to use the MAVLink protocol in custom applications with this short blog. The information was spread across different documentation and resources such as : MAVLink for Absolute Dummies, MAVLink Developer Guide, ArduPilot Docs & ArduSub GitBook. Hope this was helpful.

Cheers!

--

--