Fact-checked by Grok 2 weeks ago

MAVLink

MAVLink is a , messaging protocol designed for efficient communication between unmanned aerial vehicles (UAVs), such as , and ground stations or companion computers, as well as between onboard components. Developed in 2009 by Lorenz Meier at as part of the Pixhawk project, MAVLink has become a foundational standard in the and community for enabling real-time , over resource-constrained links. It employs a compact format to minimize bandwidth usage and ensure high reliability, making it suitable for low-power embedded systems. The protocol supports extensible message sets, allowing customization for specific applications while maintaining interoperability through standardized definitions. MAVLink is , hosted on and maintained by the Dronecode Foundation, which fosters contributions from developers worldwide to evolve the protocol. The current stable version, MAVLink 2.0 released in 2017, introduces enhancements like improved message signing for security, backward compatibility with the legacy 1.0 version, and support for advanced features such as mission planning, file transfers, and geofencing. It powers prominent open-source autopilot systems including PX4 and , facilitating applications in autonomous flight, robotics, and beyond-visual-line-of-sight operations.

Overview

Purpose and Design

MAVLink is a messaging library designed for the efficient exchange of and control between unmanned vehicles such as drones and rovers, as well as ground control stations. It enables communication in environments where systems must , commands, and status updates with minimal latency and resource usage. The protocol's design emphasizes lightness and reliability, featuring a compact format that reduces overhead compared to text-based alternatives, while avoiding dynamic memory allocation to prevent fragmentation and ensure deterministic performance in systems. Key principles include support for multiple devices sharing a single communication bus, allowing efficient of messages from various components like and actuators. Extensibility is achieved through dialects, which permit customization of message sets without altering the core protocol structure, facilitating adaptation to diverse hardware and mission requirements. MAVLink targets systems operating under severe constraints, particularly microcontrollers in unmanned aerial vehicles (UAVs) with limited and power, where even small inefficiencies could compromise or performance. In such setups, the protocol prioritizes low-latency serial-based communication, which does not require an IP stack, offering advantages over general-purpose protocols like UDP or TCP that introduce additional layering and overhead unsuitable for resource-scarce devices. This makes MAVLink particularly effective for direct, point-to-point links in bandwidth-limited scenarios, though it can also encapsulate within UDP or TCP for networked applications when needed.

Development History

MAVLink originated in 2009, when Lorenz Meier, a researcher at , developed it as a lightweight within the Pixhawk project to support open-source software for unmanned aerial vehicles. The protocol was initially released that year under the GNU Lesser General Public License (LGPL), focusing on efficient, low-overhead data exchange for resource-constrained embedded systems in drones. The first standardized version, MAVLink 1.0, was released in late 2011, marking a significant milestone that enabled broader adoption. This version was rapidly integrated into prominent open-source platforms, including —where initial support appeared in early 2011 betas—and PX4, which incorporated it upon its March 2012 launch. By 2012, MAVLink had also been adopted in early versions of QGroundControl, a cross-platform ground control station software, facilitating mission planning and real-time for developers. In response to growing needs for enhanced security and scalability, development of MAVLink 2.0 began in the mid-2010s, culminating in its release in early 2017. This update introduced message signing for authentication to mitigate spoofing risks and support for packet sizes up to 280 bytes (including the optional message signature), while maintaining with version 1.0. Governance of MAVLink transitioned in 2014 to the newly formed Dronecode Foundation, a project designed to foster open-source technologies through neutral oversight and coordinated funding. Under this structure, maintenance has been handled by a global consortium of developers, emphasizing standards that have solidified MAVLink's role in diverse unmanned systems.

Applications

Unmanned Systems

MAVLink serves as the primary for unmanned aerial vehicles (UAVs), enabling the transmission of commands such as waypoint navigation, arming and disarming, while facilitating the reception of real-time including (GPS) coordinates and (IMU) readings. In UAV operations, waypoint navigation is achieved through commands such as MAV_CMD_MISSION_START (command ID 300), sent via messages like MISSION_ITEM or DO_COMMAND, which directs the vehicle to follow pre-defined flight paths autonomously, while arming commands via COMMAND_LONG (ID 76) with parameter 400 activate or deactivate motors for sequences. Sensor telemetry, such as GPS in the GLOBAL_POSITION_INT message (ID 33) providing latitude, longitude, and altitude, and IMU via SCALED_IMU (ID 26) for acceleration and angular rates, ensures precise attitude estimation and navigation. The protocol extends to unmanned ground vehicles (UGVs) and autonomous underwater vehicles (AUVs), where it supports similar telemetry exchanges for vehicle status, environmental sensing, and command issuance over serial connections, user datagram protocol (UDP), or radio links. In UGVs, MAVLink integrates with open-source autopilots like to handle navigation commands and sensor feedback, such as odometry and obstacle detection data, transmitted via serial or radio radios for tasks like autonomous patrolling or delivery. For AUVs, adaptations like ArduSub employ MAVLink for depth control, thruster commands, and over acoustic modems or wired serial links, enabling missions in and cooperative surveying. These applications leverage the protocol's compatibility with diverse hardware interfaces to maintain low-latency data flows in resource-constrained environments. A prominent example of MAVLink integration is with Pixhawk flight controllers, which utilize the protocol over (UART) ports to enable real-time attitude control and mission planning in UAVs and compatible UGVs. In this setup, Pixhawk processes incoming MAVLink messages for roll, pitch, and yaw adjustments via the ATTITUDE_TARGET message (ID 83), while uploading mission items for sequences directly through UART lines, supporting rates up to 921600 for high-frequency updates during flight. This hardware-level integration allows seamless operation with autopilot firmware like PX4 or , minimizing latency in closed-loop control systems. MAVLink's standardized message sets promote , particularly in swarming and multi-vehicle coordination scenarios across UAVs, UGVs, and AUVs, by providing a common framework for shared commands and status broadcasts. Extensions to the protocol, such as custom messages for group formation (e.g., SWARM_SET ID 156), enable decentralized coordination where vehicles exchange formation parameters like grid spacing or leader-follower roles, facilitating applications like collaborative search patterns or fleet maintenance without centralized oversight. This shared standard reduces integration overhead, allowing heterogeneous unmanned systems to operate cohesively in mixed-domain operations.

Ground Control and Simulation

Ground control stations (GCS) rely on MAVLink to enable operators to interact with unmanned vehicles from a remote location, facilitating essential functions such as mission planning and real-time oversight. Mission Planner, a widely used GCS for -based systems, leverages MAVLink to allow real-time parameter tuning by interfacing directly with the for configuration and optimization of vehicle performance. Similarly, QGroundControl supports MAVLink-enabled autopilots from PX4 and , providing tools for vehicle setup, including parameter adjustments during flight preparation or in progress. Both stations visualize live data streamed via MAVLink, displaying vehicle position, , battery status, and other metrics on interactive maps and instrument panels to support informed decision-making. Post-flight, MAVLink facilitates the download and analysis of logs in Mission Planner, where operators can review detailed records to diagnose issues or refine future operations. In simulation environments, MAVLink enables virtual testing of vehicle behaviors without risking physical hardware, by simulating communication flows between software components. Software-in-the-Loop (SITL) setups, such as those integrated with in , use MAVLink to forward packets between the simulator and the , allowing commands like arming or takeoff to drive virtual models while sensor data returns through the protocol. For PX4-based systems, simulations employ a dedicated MAVLink to handle SITL communications, mimicking real-world interactions for multirotors, , rovers, and boats in a controlled digital space. This supports iterative , where developers test algorithms by MAVLink messages to replicate and loops, ensuring compatibility before hardware deployment. Typical workflows in GCS and simulations begin with establishing a via heartbeat messages, which are broadcast at 1 Hz to confirm system presence, type, and operational status, allowing the to detect and monitor link health. Mission uploading proceeds through a structured : the GCS sends a MISSION_COUNT message indicating the number of items, followed by sequential MISSION_ITEM messages encoding commands like MAV_CMD_NAV_WAYPOINT, which specify latitude, longitude, altitude, and actions such as loiter or takeoff for . The vehicle acknowledges receipt with MISSION_ACK, enabling the operator to verify upload success and initiate execution, all while heartbeats ensure ongoing synchronization. In simulations, this process mirrors real operations, with virtual vehicles responding to the same commands to validate logic. MAVLink extends beyond aerial applications to ground and marine domains through compatible control interfaces in GCS software. For rovers, ArduPilot's Rover firmware uses MAVLink to handle guided mode commands, enabling speed and control for autonomous following in agricultural or exploration tasks. Boat navigation software, such as extensions in ArduPilot Rover, leverages the for waypoint-based missions on water, supporting thruster commands and obstacle avoidance via the same message sets. These implementations maintain consistency, allowing unified GCS tools like Mission Planner to manage diverse vehicle types with minimal reconfiguration.

Protocol Specification

Packet Format

The MAVLink employs a compact packet structure designed for low-bandwidth, communication in systems. Each packet begins with a start (STX) byte: 0xFE for and 0xFD for version 2, signaling the packet's initiation and version to the receiver. Following the STX is the payload length field (1 byte, uint8_t), indicating the number of bytes in the subsequent , with a maximum of 255 bytes to maintain efficiency. The sequence number (1 byte, uint8_t) follows, which increments with each transmitted packet from a given component to enable detection of lost messages and maintain order during transmission. Next are the system ID (1 byte, uint8_t) and component ID (1 byte, uint8_t) fields, which identify the originating system and its specific subsystem or component (e.g., vs. camera), facilitating routing in multi-device networks where multiple vehicles or components communicate simultaneously. The message ID field specifies the type and structure of the data within the payload. In MAVLink 1, this is a 2-byte (uint16_t), limiting the protocol to possible message types. MAVLink 2 extends this to a 3-byte ( bits, supporting up to 16,777,215 message IDs). In code, it is typically represented as a uint32_t with the upper 8 bits unused. The payload itself is a of up to 255 bytes containing the actual message data, such as readings or commands, serialized in a order (largest first) for consistent parsing across implementations. MAVLink 2 introduces additional 1-byte flags before the sequence: incompatible flags (for breaking changes like extended IDs) and compatible flags (for optional extensions without altering v1 compatibility). An optional 13-byte in MAVLink 2 (1-byte link ID + 6-byte + 6-byte cryptographic ) can be appended for , increasing the maximum packet size to 280 bytes when present. The packet concludes with a 2-byte (uint16_t) for integrity verification.
FieldMAVLink 1 SizeMAVLink 2 SizePurpose
STX (Magic)1 byte (0xFE)1 byte (0xFD)Packet start and version indicator.
Payload Length1 byte1 byteSize of payload (0-255 bytes).
Incompatible FlagsN/A1 byteFlags for v2-specific incompatible changes.
Compatible FlagsN/A1 byteFlags for v2-compatible extensions.
1 byte1 byteMessage ordering and loss detection.
System ID1 byte1 byteOriginating system identifier.
Component ID1 byte1 byteOriginating component identifier.
2 bytes3 bytesMessage type identifier.
0-255 bytes0-255 bytesMessage data.
2 bytes2 bytesError detection checksum.
Signature (opt.)N/A13 bytesAuthentication data (v2 only).
The ensures reliable transmission by detecting corruption, computed using the CRC-16-CCITT algorithm with the X.25 (0x1021, equivalent to x¹⁶ + x¹² + x⁵ + 1). It is calculated over the bytes from the payload length through the payload, excluding the STX, and XORed with a message-specific extra value (a predefined constant per for added uniqueness). The computation initializes the CRC accumulator to 0xFFFF and processes each byte using a 256-entry for efficiency, as implemented in the reference C code. Pseudocode for CRC computation (adapted from the MAVLink reference implementation):
function mavlink_crc_accumulate(crc, byte):
    tmp = byte ^ (crc & 0xFF)
    crc = (crc >> 8) ^ crc_table[tmp]
    return crc

function mavlink_crc_calculate(msgid, payload, payload_len, extra_crc):
    crc = 0xFFFF  # Initialize
    # Accumulate header fields (excluding STX)
    crc = mavlink_crc_accumulate(crc, payload_len)
    crc = mavlink_crc_accumulate(crc, sequence)
    crc = mavlink_crc_accumulate(crc, sysid)
    crc = mavlink_crc_accumulate(crc, compid)
    # Accumulate msgid (all bytes)
    for i in 0 to sizeof(msgid)-1:
        crc = mavlink_crc_accumulate(crc, msgid_bytes[i])
    # Accumulate payload
    for i in 0 to payload_len-1:
        crc = mavlink_crc_accumulate(crc, payload[i])
    # XOR with message-specific extra
    crc ^= extra_crc
    return crc  # Low byte first, then high byte in packet
This table-driven approach minimizes computational overhead on resource-constrained devices.

Message Set and Dialects

The MAVLink protocol employs a modular message set that standardizes communication between unmanned systems, ground stations, and other components. At its core is the "common" message set, which provides essential definitions for basic operations across diverse platforms. This set includes messages such as (message ID 0), which reports system status including type, autopilot version, mode, and health; (message ID 30), which conveys vehicle orientation data like roll, , yaw, and angular rates; and COMMAND_LONG (message ID 76), which enables the transmission of parameterized commands for actions such as takeoff, , or waypoint navigation. These messages form the foundational layer, ensuring while allowing for extensions in specialized applications. Dialects in MAVLink extend the common set to accommodate domain-specific requirements, defined through XML schemas that specify message IDs, field types (e.g., integers, floats, enums), lengths, and descriptions. Key examples include common.xml for universal standards and ardupilotmega.xml for systems, which adds vehicle-tailored messages while inheriting the core set. These XML files serve as input for code generation tools, such as the mavgen script, which produces language-specific implementations—including C++ headers and classes—for parsing and , facilitating integration into systems or applications. The structure promotes consistency, with enums defining symbolic constants (e.g., MAV_TYPE for vehicle types) to enhance readability and reduce errors. MAVLink 2 builds on by introducing enhancements to message handling, including high-resolution 64-bit timestamps (e.g., time_us fields) for precision in timing-critical data like readings, and extended 32-bit enums that support up to 4 billion unique values per category, enabling more granular state representations without breaking compatibility. These updates are backward-compatible, allowing MAVLink 1 systems to ignore unfamiliar fields while MAVLink 2 parsers leverage the full capabilities. Customization of dialects involves editing or creating XML files to add messages relevant to particular use cases, such as the ardupilotmega dialect's inclusion of messages like FENCE_POINT (ID 160) for definitions or WINCH_STATUS (ID 173) for winch operations in systems. Developers must adhere to guidelines for allocation (typically above 255 for extensions) and field ordering to preserve wire , ensuring that updated dialects can coexist with implementations in mixed environments. This process, managed through the official MAVLink , allows communities like to evolve the protocol iteratively without disrupting the ecosystem.

Security and Reliability

Vulnerabilities

MAVLink's design prioritizes lightweight communication for resource-constrained unmanned systems, but this results in the absence of built-in , leaving messages transmitted in over radio links such as 433 MHz or 915 MHz radios. This exposes sensitive data, including , GPS coordinates, and control commands, to by anyone within radio range using off-the-shelf receivers. Consequently, attackers can intercept and analyze flight paths or operational details, facilitating subsequent spoofing or replay attacks where recorded packets are retransmitted to disrupt or hijack operations. In MAVLink , the lack of any mechanism allows unauthorized command injection, enabling attackers to send forged packets that mimic legitimate control station (GCS) instructions, such as altering waypoints or arming/disarming motors. This flaw stems from the protocol's reliance on unverified system IDs and component IDs in packet headers, permitting man-in-the-middle (MITM) interceptions over open wireless channels without detection. Field experiments have demonstrated 100% success rates for such attempts in uncontrolled environments, underscoring the protocol's susceptibility to integrity breaches. A notable exploit highlighting these issues occurred in 2015, where researchers demonstrated hijacking by exploiting the unencrypted transmission of the network ID (NetID) in MAVLink frames over WiFi-forwarded links. By sniffing the NetID and injecting commands via a low-cost radio module connected to a , attackers could disarm or redirect quadcopters equipped with Pixhawk autopilots, bypassing any session validation. This vulnerability, requiring minimal code—three lines in —affected systems using MAVLink for WiFi-to-radio bridging, common in setups. Additional risks include buffer overflows triggered by malformed packets, which can crash and cause denial-of-service (). For instance, oversized or corrupted MAVLink messages of type TRAJECTORY_REPRESENTATION_WAYPOINTS in versions up to 1.12.3 lead to stack-based overflows, halting vehicle control during flight. Similarly, DoS attacks via flooding invalid packet sequences overwhelm GCS-UAV channels, increasing by up to 0.11 seconds and preventing legitimate commands from processing, as validated in empirical tests. Historical incidents further illustrate these flaws. By 2018, reports highlighted GPS spoofing vulnerabilities in MAVLink-dependent autopilots, where attackers injected falsified HIL_GPS messages to mislead navigation, causing drones to deviate from intended paths in simulated and real-world tests. MAVLink 2 introduces optional to address some gaps, though adoption remains incomplete.

Enhancements and Best Practices

MAVLink 2 introduces message signing as a enhancement for , where the field appends 13 bytes to packets: a 1-byte link ID, a 6-byte (microseconds since boot or a reference time), and a 6-byte signature. This signature is the first 48 bits of an HMAC-SHA256 hash computed over the packet (excluding the signature itself), the previous signature, incompatible/compatibility flags, sequence number, system ID, component ID, and message length using a 32-byte secret . Receivers verify by recomputing the hash with the shared and comparing the signatures, authenticating the source, ensuring integrity, and preventing replay attacks through the chained computation and . To bolster reliability, MAVLink 2 incorporates an 8-bit sequence number in each packet header, enabling endpoints to detect missing or out-of-order messages and trigger application-level retransmission requests when necessary. Additionally, the protocol uses a 16-bit CRC-16/MCRF4XX calculated over the entire packet, including version-specific elements, providing robust end-to-end error detection beyond basic transmission integrity checks. When combined with signing, this offers layered validation, as the signature serves as a secondary checksum resistant to certain corruption patterns. Best practices for deploying MAVLink emphasize adopting version 2 exclusively to leverage its expanded features and security options, including enabling signing on all links with securely generated and exchanged keys. Network configurations should incorporate firewalls to restrict access to standard ports such as 14550, limiting inbound connections to trusted IP ranges and preventing unauthorized access. For , since MAVLink lacks native , links should be secured using VPNs or custom wrappers like tunnels to protect against over wireless or public networks. Ongoing developments in MAVLink security explore proposals for quantum-resistant signing algorithms to future-proof against emerging computational threats, alongside integrations with protocols like for seamless in IP-based UAV networks. As of 2025, research has introduced proposals like the MAVShield for encrypting MAVLink communications and experimental evaluations of securing links in systems like drones. These efforts aim to address the protocol's lightweight design constraints while supporting advanced applications in multi-vehicle swarms and ecosystems.

Ecosystem

Implementations and Libraries

The official MAVLink library is a lightweight, header-only implementation in C, designed for efficient communication in resource-constrained environments such as embedded systems. It serves as the reference implementation, consisting primarily of message-set definitions in XML format that are used to generate code for parsing and serializing MAVLink packets. The library is MIT-licensed, allowing unrestricted use in both open- and closed-source projects without requiring source code publication. To support multiple programming languages, the official toolchain includes generators that produce libraries from the XML message definitions. These generators support MAVLink 2 and MAVLink 1, creating code for C, C++11 (with modern features like std::variant for extensible messages), Python, TypeScript, Java, and Lua (WLua variant). The primary generator tool, mavgen.py, is a Python-based command-line utility (with a GUI option via mavgenerate.py) that compiles dialects into language-specific headers and source files, enabling developers to integrate custom or standard message sets without manual protocol handling. Key community-maintained implementations build on this foundation to provide higher-level abstractions. Pymavlink is a library offering low-level message processing for scripting and automation, including utilities for connecting to serial ports, , or links, and it has been widely adopted for prototyping MAVLink interactions in ground control systems. MAVSDK provides a high-level across languages like , , and , abstracting MAVLink details through a gRPC-based core for tasks such as vehicle discovery, subscription, and management, making it suitable for application on desktops and mobile platforms. For embedded use, the libmavlink library (generated via mavgen) is optimized for minimal and flash usage, supporting deterministic parsing on microcontrollers. MAVLink libraries are deployed across diverse platforms, including real-time operating systems like in the PX4 autopilot stack for onboard flight controllers, where they handle low-latency message routing in safety-critical environments. On desktop environments, such as or Windows, these libraries facilitate ground control station (GCS) development by integrating with higher-level frameworks for simulation and monitoring. All major implementations handle both MAVLink versions 1.0 and 2.0, with v2 libraries maintaining to parse v1 packets while adding features like signing and extensible fields. Developers use tools like mavgenerate.py to compile specific dialects (e.g., common.xml for standard messages) into version-appropriate code, ensuring across mixed-version networks.

Tools and Integrations

MAVProxy serves as a command-line ground control station (GCS) for MAVLink-enabled systems, providing a minimalist and extensible interface for monitoring, controlling, and scripting unmanned aerial vehicles (UAVs). It supports features like waypoint management, parameter tuning, and telemetry forwarding over UDP or serial connections, making it suitable for embedded applications on resource-constrained devices. The MAVLink Inspector, integrated into tools like QGroundControl and Mission Planner, enables real-time packet debugging by displaying incoming MAVLink messages, their values, and trends in a graphical format. For custom dialects, the MAVLink code generator (mavgen) automates the creation of language-specific libraries from XML message definitions, allowing developers to extend the protocol without manual implementation. Hardware integrations commonly include SiK radios, which provide long-range telemetry links for MAVLink communication, achieving ranges exceeding 300 meters out-of-the-box through open-source on low-cost transceivers operating at 433 MHz or 915 MHz frequencies. Companion computers such as the often run ROS with the MAVROS bridge to facilitate MAVLink-to-ROS message translation, enabling onboard processing for tasks like while maintaining compatibility with autopilots like PX4 or . Third-party extensions extend MAVLink's utility in and environments; for instance, MAVROS supports ROS 2 , bridging MAVLink messages to ROS 2 topics for distributed systems in multi-robot applications. Plugins for simulators like leverage MAVLink through SITL to simulate MAVLink traffic, allowing testing of behaviors in realistic physics environments. Community contributions enhance MAVLink's ecosystem through tools like MAVLink Router, which forwards messages across multiple serial and IP endpoints to support multi-device setups, such as connecting a GCS, companion computer, and peripherals simultaneously. Analysis tools, including MavLogAnalyzer, parse MAVLink log files from sources like QGroundControl or onboard storage, enabling flight data visualization, error detection, and performance metrics extraction for post-mission review.

References

  1. [1]
    Protocol Overview - MAVLink Guide
    MAVLink is a binary telemetry protocol designed for resource-constrained systems and bandwidth-constrained links.
  2. [2]
    MAVLink Developer Guide
    MAVLink is a very lightweight messaging protocol for communicating with drones (and between onboard drone components).Protocol Overview · MAVLINK Common Message... · Getting Started · MAVLink 2
  3. [3]
    [PDF] Micro Air Vehicle Link (MAVLink) in a Nutshell: A Survey - arXiv
    Jun 22, 2019 · It specifies a comprehensive set of messages exchanged between unmanned systems and ground stations. This protocol is used in major autopilot ...
  4. [4]
    The history of Pixhawk - Auterion
    The story begins with a quest for autonomous flight. Lorenz wanted to make drones fly autonomously using computer vision, so he started a research project.
  5. [5]
    Release Notes — Plane documentation - ArduPilot
    June 15, 2012: Plane 2.40 released. Supports MAVLink 1.0, new 3DR Ublox GPS module, improved dataflash erase to ensure fast startup on first use, fixed an ...
  6. [6]
    PX4 Autopilot Software - GitHub
    This repository holds the PX4 flight control solution for drones, with the main applications located in the src/modules directory.Releases · Issues 1.4k · Pull requests 543 · Actions
  7. [7]
    MAVLink Versions
    MAVLink v1.0: Widely adopted around 2013. Still used by a number of legacy peripherals. The MAVLink 2.0 C/C++ and Python libraries are backwards compatible ...
  8. [8]
    MAVLink 2
    MAVLink 2 is a backward-compatible update to the MAVLink protocol that has been designed to bring more flexibility and security to MAVLink communication.
  9. [9]
    Mission Protocol - MAVLink Guide
    MAVLink 2 supports three types of "missions": flight plans, geofences and rally/safe points. The protocol uses the same sequence of operations for all types ( ...
  10. [10]
    Arming and Disarming — Dev documentation - ArduPilot
    This page explains how MAVLink can be used by a ground station or companion computer to arm or disarm a vehicle.
  11. [11]
    MAVLINK Common Message Set (common.xml)
    The MAVLink common message set contains standard definitions that are managed by the MAVLink project. The definitions cover functionality that is considered ...
  12. [12]
  13. [13]
  14. [14]
    [PDF] Autonomous Underwater Vehicle: Electronics and Software ... - arXiv
    The maneuvering algorithm uses the MAVLink protocol of the ArduSub project for movement and its simulation. Key Words​: ​Autonomous Underwater Vehicle, Odroid.
  15. [15]
    MAVLink Basics — Dev documentation - ArduPilot
    MAVLink is a serial protocol most commonly used to send data and commands between vehicles and ground stations.
  16. [16]
    (PDF) Towards a Unified Decentralized Swarm Management and ...
    Aug 2, 2017 · This paper proposes a comprehensive set of coordination commands necessary for the communication between swarm MAVs and ground entities.
  17. [17]
    [PDF] Underwater Acoustic Mavlink Communication for Swarming AUVS
    Apr 5, 2021 · Summary. The objective of this project is to conduct an underwater survey. The primary goal is to develop a device that can.
  18. [18]
    Mission Planner Overview — Mission Planner documentation
    ### Summary of Mission Planner's Use of MAVLink
  19. [19]
    QGroundControl Guide (Daily Builds) | QGC Guide
    ### Summary of QGroundControl's Use of MAVLink
  20. [20]
    Using SITL with Gazebo — Dev documentation - ArduPilot
    To use SITL with Gazebo, install ArduPilot SITL, Gazebo, and the ArduPilot Gazebo plugin. Then, run Gazebo and SITL with example models.
  21. [21]
    PX4/PX4-SITL_gazebo-classic: Set of plugins, models and ... - GitHub
    PX4 Gazebo Plugin Suite for MAVLink SITL and HITL. Build Status MacOS Build Tests. This is a flight simulator for rovers, boats, multirotors, VTOL, fixed wing.
  22. [22]
    Rover Commands in Guided Mode — Dev documentation - ArduPilot
    This page explains how MAVLink can be used by a ground station or companion computer to control the motion of a Rover or Boat while in Guided mode.
  23. [23]
    Mission Commands — Rover documentation - ArduPilot
    This article describes the mission commands that are supported by Copter, Plane, Sub and Rover when switched into Auto mode. Note. there are many other MAVLink ...<|control11|><|separator|>
  24. [24]
    ArduPilot Rover — Rover documentation
    ### MAVLink Use in Rover and Boat Control Interfaces
  25. [25]
    Packet Serialization - MAVLink Guide
    The packet format includes a 2-byte CRC-16/MCRF4XX to allow detection of message corruption. See the MAVLink source code for the documented C-implementation.
  26. [26]
    mavlink/mavlink: Marshalling / communication library for drones.
    MAVLink is a very lightweight, header-only message library for communication between drones and/or ground control stations.
  27. [27]
    Dialect: ArduPilotMega - MAVLink Guide
    ardupilotmega.xml contains the documentation for this dialect as used by the ArduPilot flight stack. The documentation here may not be a precise match if, for ...
  28. [28]
    [PDF] Vulnerability Analysis of the MAVLink Protocol for Command ... - DTIC
    Mar 11, 2014 · The MAVLink protocol is an open source, point-to-point networking protocol used to carry telemetry and to command and control many small ...Missing: arming | Show results with:arming
  29. [29]
    (PDF) Micro Air Vehicle Link (MAVlink) in a Nutshell: A Survey
    Jun 19, 2019 · This is the first technical survey and tutorial on the MAVLink protocol, which represents an important reference for unmanned systems users and developers.
  30. [30]
  31. [31]
    PX4 Military UAV Autopilot 1.12.3 - Denial of Service (DoS)
    Jun 26, 2025 · A stack-based buffer overflow vulnerability in PX4 Military UAV Autopilot <=1.12.3 is triggered when handling a malformed MAVLink message.
  32. [32]
    [PDF] GPS Spoofing on UAV Simulation using Ardupilot - ASEE PEER
    The ability to simulate GPS spoofing allows us to study how navigation systems on. UAVs respond to GPS spoofing attacks and to develop detection and mitigation ...
  33. [33]
    Message Signing (Authentication) - MAVLink Guide
    MAVLink 2 adds support for message signing, which allows a MAVLink system to verify that messages originate from a trusted source.
  34. [34]
  35. [35]
    [PDF] UAS Cyber Security and Safety Literature Review - FAA's ASSURE
    Mar 23, 2022 · Hardware Design Best Practices: The topic of best practices regarding designing UAV hardware ... Securing the MAVLink Protocol for ...
  36. [36]
    Generating MAVLink Libraries
    These generators can build MAVLink 2 and MAVLink 1 libraries for the following programming languages: C, C++11, Python, Typescript, Java, and WLua. The ...
  37. [37]
    Using Pymavlink Libraries (mavgen) - MAVLink Guide
    MAVLink is the main protocol handling class. It is defined in each dialect module, and includes a <message_name>_send() method for all messages in the dialect's ...<|control11|><|separator|>
  38. [38]
    MAVSDK (main / v3) | MAVSDK Guide
    MAVSDK is a collection of libraries for various programming languages to interface with MAVLink systems such as drones, cameras or ground systems.MAVSDK C++ Library · MAVSDK-Python · Class Mavsdk · QuickStart
  39. [39]
    Using C MAVLink Libraries (mavgen)
    The MAVLink C library generated by mavgen is a header-only implementation that is highly optimized for resource-constrained systems with limited RAM and flash ...
  40. [40]
    MAVLink Messaging | PX4 Guide (main)
    MAVLink is a lightweight protocol that was designed for efficiently sending messages over unreliable low-bandwidth radio links. Messages are simplest and most " ...<|control11|><|separator|>
  41. [41]
    MAVProxy documentation - ArduPilot
    MAVProxy is a fully-functioning GCS for UAV's, designed as a minimalist, portable and extendable GCS for any autonomous system supporting the MAVLink protocol.Quickstart · MAVProxy Cheatsheet · Download and Installation · Getting Started
  42. [42]
    ArduPilot/MAVProxy: MAVLink proxy and command line ground station
    MAVProxy. This is a MAVLink ground station written in python. Please see https://ardupilot.org/mavproxy/index.html for more information.Sign in · Pull requests · Activity · Releases 16
  43. [43]
    MAVLink Inspector | QGC Guide (4.3)
    The MAVLink Inspector provides real-time information and charting of MAVLink traffic received by QGroundControl.
  44. [44]
    Mission Planner Advanced Tools - ArduPilot
    MAVLink Inspector¶. This allows a real time inspection of the MAVLink values being sent. A user can see any measurement/reading being sent and normally stored ...
  45. [45]
    SiK Telemetry Radio — Copter documentation - ArduPilot
    A SiK Telemetry Radio is a small, light and inexpensive open source radio platform that typically allows ranges of better than 300m “out of the box”SiK Radio configuration · Telemetry Radio Regional... · 3DR Radio v1
  46. [46]
    Telemetry Radios/Modems | PX4 Guide (main)
    Telemetry Radios can (optionally) be used to provide a wireless MAVLink connection between a ground control station like QGroundControl and a vehicle running ...
  47. [47]
    ROS (1) with MAVROS Installation Guide | PX4 Guide (main)
    MAVROS is a ROS 1 package that enables MAVLink extendable communication between computers running ROS 1 for any MAVLink enabled autopilot, ground station, or ...
  48. [48]
    Communicating with Raspberry Pi via MAVLink — Dev documentation
    This page explains how to connect and configure a Raspberry Pi (RPi) so that it is able to communicate with a flight controller using the MAVLink protocol over ...
  49. [49]
    mavlink/mavros: MAVLink to ROS gateway with proxy for ... - GitHub
    MAVLink extendable communication node for ROS. mavros package It is the main package, please see its README. Here you may read installation instructions.
  50. [50]
    mavros 2.9.0 documentation - ROS documentation
    MAVLink extendable communication node for ROS2. ROS API documentation moved to wiki.ros.org. Features Limitations Only for Linux.Missing: integration | Show results with:integration
  51. [51]
    MavLinkCom - AirSim
    MavLinkCom is a cross-platform C++ library that helps connect to and communicate with MavLink based vehicles. Specifically this library is designed to work ...
  52. [52]
    Home - AirSim - Microsoft Open Source
    AirSim is a simulator for drones, cars and more, built on Unreal Engine (we now also have an experimental Unity release). It is open-source, cross platform.PX4/MavLink Logging · AirSim with Unity · AirSim on Azure · Who is Using AirSim
  53. [53]
    Route mavlink packets between endpoints - GitHub
    MAVLink Router is an application to distribute MAVLink messages between multiple endpoints (connections). It distributes packets to a single port or multiple ...
  54. [54]
    Routing - MAVLink Guide
    The MAVLink Router can be used to mix-and-match different IP protocols with serial ports in order to route MAVLink traffic.
  55. [55]
    mbeckersys/MavLogAnalyzer - GitHub
    Parse MavLink Logfiles as they are created by, e.g., QGroundControl; Parse onboard logs of APM:Copter and PX4; merge flights (e.g., entire day of flight ...