MAVLINK Communication Protocol

NEWS: MAVLINK will be evolved to be SAE AS-4 compatible in the next months. The goal is to create a kind of AS-4 light

C code / XML Configuration file

Overview

One packet of the MAVLink protocol looks like this. It is inspired by the CAN [ http://en.wikipedia.org/wiki/Controller_Area_Network ] and SAE AS-4 standards.

Byte Index Content Value
0 Packet start sign 0x55, ASCII: U
1 Payload length 0 - 255
2 Packet sequence 0 - 255
3 System ID (7 bit) + ACK (1 bit) 0 - 127
4 Component ID 0 - 255
5 Message ID 0 - 255
6 to (n+6) Data (0 - 255) bytes
(n+7) to (n+7) Checksum (high byte, low byte) SAE AS-4/ITU X.25 hash

Performance

This protocol was totally geared towards two properties: Transmission speed and safety. It allows to check the message content, it also allows to detect lost messages but still only needs six bytes overhead for each packet.

Transmission examples

Link speed Hardware Update rate Payload Float values
115200 baud XBee Pro 2.4 GHz 50 Hz 224 bytes 56
115200 baud XBee Pro 2.4 GHz 100 Hz 109 bytes 27
57600 baud XBee Pro 2.4 GHz 100 Hz 51 bytes 12
9600 baud XBee Pro XSC 900 50 Hz 13 bytes 3
9600 baud XBee Pro XSC 900 20 Hz 42 bytes 10

These numbers have been calculated with these formulas:

Net bandwidth of a serial link in bytes per second

[Image]

Net bandwidth of the protocol

[Image]

Message ID

The Message ID is a unique ID for a message type. Below you see the different types existing until now. The range from 0 to 127 is reserved for status messages and data. The range from 128 to 255 is reserved for command messages.

Sequence

This is a Number between 0 and 255. Its a continuous massage counter which starts from 0 again if it would be bigger than 255. With the Sequence number you can check if a message has been lost during the transfer.

Length

The Length is the number of bytes in the data section of the message. It can be between 0 and 255. So it's possible to send 255 bytes per massage.

Data

In here is the data of the message. It can be up to 255 bytes.

Checksum

The checksum has 16 bits and is based on the ITU X.25 / SAE AS-5 checksum polynomial.

Byte Order

The protocol uses network order, which is big endian [ http://en.wikipedia.org/wiki/Endianess ].

Usage / Code Example

#include "mavlink.h"
 
/**
 * Send values out via UART (serial)
 */
void send_something()
{ 
  // Attitude struct - generated from XML by MAVLink
  attitude_t attitude;
  // Enter current attitude values - from sensors
  attitude.roll = 0.5f;
  attitude.pitch = 0.2f;
 
  // MAVLink message container
  mavlink_message_t msg;
  // UART buffer
  uint8_t send_buf[MAVLINK_MAX_PACKET_LEN];
 
  // Pack message into MAVLink packet (variable length)
  uint32_t len = message_attitude_encode(send_buf, &msg, attitude);
  // Send message
  your_uart_send_routine(send_buf, len);
 
}
 
/**
 * The main loop - filters sensor data, sends out data and parses incoming data
 */
void main()
{
 
  while(1)
  {
    send_something();
    // Parse messages from groundstation
    mavlink_message_t msg; // Will hold a newly received message
 
    uint8_t buf[1024];
    uint32_t bytes_count = get_bytes_from_uart(buf, sizeof[buf]);
 
    // Parse buffer, looking for new messages
    for (int i = 0; i < bytes_count; i++)
    {
      if (mavlink_parse_char(COMM_0, buf[i], &msg))
      {
        // Found new message
        switch (msg.msgid)
        {
          // Check for incoming actions
          // and execute them (e.g. motor on, liftoff, etc.)
          case MAVLINK_MSG_ID_ACTION:
          {
            action_t act;
            message_action_decode(&msg, &act);
            if (act.targe = THIS_SYSTEM_ID)
            {
              // Execute action (identified by unsigned char action id)
              execute_action(act.action);
            }
          }
          break;
        }
      }
    }
 
}

Messages

Messages are defined by the mavlink.xml file. The C packing/unpacking code is generated from this specification.

<?xml version="1.0"?>
<messages>

	<message name="HEARTBEAT" id="0">
		<field name="type" type="uint8_t">Type of the MAV (quadrotor, helicopter, etc.)</field>
	</message>

	<message name="BOOT" id="1">
		<field name="version" type="uint32_t">The onboard software version</field>
	</message>

	<message name="ACTION" id="20">
		<field name="target" type="uint8_t">The system executing the action</field>
		<field name="action" type="uint8_t">The action id</field>
	</message>

	<message name="SET_MODE" id="21">
		<field name="target" type="uint8_t">The system setting the mode</field>
		<field name="mode" type="uint8_t">The new mode</field>
	</message>

	<message name="MANUAL_CONTROL" id="50">
		<field name="target" type="uint8_t">The system to be controlled</field>
		<field name="roll" type="float">roll</field>
		<field name="pitch" type="float">pitch</field>
		<field name="yaw" type="float">yaw</field>
		<field name="thrust" type="float">thrust</field>
		<field name="roll_manual" type="uint8_t">roll control enabled auto:0, manual:1</field>
		<field name="pitch_manual" type="uint8_t">pitch auto:0, manual:1</field>
		<field name="yaw_manual" type="uint8_t">yaw auto:0, manual:1</field>
		<field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
	</message>

	<message name="RAW_SENSOR" id="100">
		<field name="msec" type="uint32_t">Timestamp (milliseconds)</field>
		<field name="xacc" type="uint32_t">X acceleration (mg raw)</field>
		<field name="yacc" type="uint32_t">Y acceleration (mg raw)</field>
		<field name="zacc" type="uint32_t">Z acceleration (mg raw)</field>
		<field name="xgyro" type="uint32_t">Angular speed around X axis (adc units)</field>
		<field name="ygyro" type="uint32_t">Angular speed around Y axis (adc units)</field>
		<field name="zgyro" type="uint32_t">Angular speed around Z axis (adc units)</field>
		<field name="xmag" type="uint32_t">X Magnetic field (milli tesla)</field>
		<field name="ymag" type="uint32_t">Y Magnetic field (milli tesla)</field>
		<field name="zmag" type="uint32_t">Z Magnetic field (milli tesla)</field>
		<field name="baro" type="int32_t">Barometric pressure (hecto Pascal)</field>
		<field name="gdist" type="uint32_t">Ground distance (meters)</field>
		<field name="temp" type="int32_t">Temperature (degrees celcius)</field>
	</message>

	<message name="RAW_IMU" id="101">
		<field name="msec" type="uint32_t">Timestamp (milliseconds)</field>
		<field name="xacc" type="uint32_t">X acceleration (mg raw)</field>
		<field name="yacc" type="uint32_t">Y acceleration (mg raw)</field>
		<field name="zacc" type="uint32_t">Z acceleration (mg raw)</field>
		<field name="xgyro" type="uint32_t">Angular speed around X axis (adc units)</field>
		<field name="ygyro" type="uint32_t">Angular speed around Y axis (adc units)</field>
		<field name="zgyro" type="uint32_t">Angular speed around Z axis (adc units)</field>
		<field name="xmag" type="uint32_t">X Magnetic field (milli tesla)</field>
		<field name="ymag" type="uint32_t">Y Magnetic field (milli tesla)</field>
		<field name="zmag" type="uint32_t">Z Magnetic field (milli tesla)</field>
	</message>

	<message name="RAW_AUX" id="102">
		<field name="adc1" type="uint32_t">ADC1 (J405 ADC3, LPC2148 AD0.6)</field>
		<field name="adc2" type="uint32_t">ADC2 (J405 ADC5, LPC2148 AD0.2)</field>
		<field name="adc3" type="uint32_t">ADC3 (J405 ADC6, LPC2148 AD0.1)</field>
		<field name="adc4" type="uint32_t">ADC4 (J405 ADC7, LPC2148 AD1.3)</field>
		<field name="vbat" type="uint32_t">Battery voltage</field>
		<field name="temp" type="int32_t">Temperature (degrees celcius)</field>
		<field name="baro" type="int32_t">Barometric pressure (hecto Pascal)</field>
	</message>

	<message name="SYS_STATUS" id="103">
		<field name="mode" type="uint8_t">System mode</field>
		<field name="status" type="uint8_t">System status flag</field>
		<field name="vbat" type="uint16_t">Battery voltage</field>
		<field name="motor_block" type="uint8_t">Motor block status flag</field>
		<field name="packet_drop" type="uint16_t">Dropped packets</field>
	</message>

	<message name="SET_CAM_SHUTTER" id="70">
		<field name="cam_id" type="uint16_t">Camera id</field>
		<field name="cam_mode" type="uint8_t">Camera mode: 0 = auto, 1 = manual</field>
		<field name="trigger_pin" type="uint8_t">Trigger pin, 0-3 for PtGrey FireFly</field>
		<field name="interval" type="uint16_t">Shutter interval, in microseconds</field>
		<field name="exposure" type="uint16_t">Exposure time, in microseconds</field>
		<field name="gain" type="float">Camera gain</field>
	</message>

	<message name="PARAM_REQUEST_READ" id="80">
		<field name="param_id" type="uint16_t">Camera id</field>
	</message>

	<message name="PARAM_VALUE" id="80">
		<field name="param_id" type="uint16_t">Onboard parameter id</field>
		<field name="param_value" type="float">Onboard parameter value</field>
	</message>

	<message name="PARAM_WRITE" id="80">
		<field name="param_id" type="uint16_t">Onboard parameter id</field>
		<field name="param_value" type="float">Onboard parameter value</field>
	</message>

	<message name="ATTITUDE" id="90">
		<field name="msec" type="uint32_t">Timestamp (milliseconds)</field>
		<field name="roll" type="float">Roll angle (rad)</field>
		<field name="pitch" type="float">Pitch angle (rad)</field>
		<field name="yaw" type="float">Yaw angle (rad)</field>
		<field name="rollspeed" type="float">Roll angular speed (rad/s)</field>
		<field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
		<field name="yawspeed" type="float">Yaw angular speed (rad/s)</field>
	</message>

</messages>

Last modified: 2010/04/05 17:39

Copyrigth 2010 http://pixhawk.ethz.ch/software/mavlink