Mission Protocol

The mission sub-protocol allows a GCS or developer API to manage mission (flight plan), geofence and safe point information on a drone/component.

The protocol covers:

  • Operations to upload, download and clear missions, set/get the current mission item number, and get notification when the current mission item has changed.
  • Message type(s) for exchanging mission items.
  • Mission commands that are common to most autpilots/GCS.

The protocol follows the client/server pattern, where operations (and most commands) are initiated by the GCS/developer API (client) and acknowledged by the autopilot (server).

The protocol supports re-request of messages that have not arrived, allowing missions to be reliably transferred over a lossy link.

Mission Types

MAVLink 1 supports only "regular" flight-plan missions. MAVLink 2 supports three types of "missions": flight plans, geofence and rally/safe Points (the vehicle must store and act on these separately).

The mission type is specified in a MAVLink 2 message extension field: mission_type using one of the MAV_MISSION_TYPE enum values:

You set the mission_type in messages: MISSION_COUNT, MISSION_REQUEST, MISSION_ITEM_INT, MISSION_CLEAR_ALL, etc.

The protocol uses the same sequence of operations for all types (albeit with different mission commands).

Mission Commands

MAVLink commands are defined in the MAV_CMD enum.

  • Some commands can be sent outside of a mission context using the Command Protocol.
  • Not all commands in MAV_CMD are supported by all systems (or all flight modes).

The mission commands are broadly divided into three groups.

  • NAV commands (MAV_CMD_NAV_*) for navigation/movement - e.g. setting waypoints, taking off/landing, etc.
  • DO commands (MAV_CMD_DO_*) for immediate actions like changing speed or activating a servo.
  • CONDITION commands (MAV_CMD_CONDITION_*) for changing the execution of the mission based on a condition - e.g. pausing the mission for a time before executing next command.

The commands are transmitted/encoded in MISSION_ITEM or MISSION_ITEM_INT messages. These messages include fields to identify the desired command (command id) and up to 7 command-specific parameters. The first four parameters can be used for any purpose (depends on the particular command). The last three parameters (x, y, z) are used for positional information in NAV commands, but can be used for any purpose in other commands.

The command-specific fields in the messages are shown below:

Field NameTypeValuesDescription
commanduint16_tMAV_CMDCommand id, as defined in MAV_CMD.
param1floatParam #1.
param2floatParam #2.
param3floatParam #3.
param4floatParam #4.
xfloat / int32_tX coordinate (local frame) or latitude (global frame) for navigation commands (otherwise Param #5).
yfloat / int32_tY coordinate (local frame) or longitude (global frame) for navigation commands (otherwise Param #6).
zfloatZ coordinate (local frame) or altitude (global - relative or absolute, depending on frame) (otherwise Param #7).

The remaining message fields are used for addressing, defining the mission type, specifying the frame used for x, y, z in NAV messages, etc.:

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence number for
frameuint8_tMAV_FRAMEThe coordinate system of the waypoint.
ArduPilot and PX4 both only support global frames in mission commands (local frames may be supported if the same command is sent via the command protocol).
mission_typeuint8_tMAV_MISSION_TYPEMission type.
currentuint8_tfalse:0, true:1When downloading, whether the item is the current mission item.
autocontinueuint8_tAutocontinue to next waypoint when the command completes.

Operations

This section explains the main operations defined by the protocol.

Upload a Mission to the Vehicle

The diagram below shows the communication sequence to upload a mission to a drone (assuming all operations succeed).

GCSDroneMISSION_COUNTStart timeoutMISSION_REQUEST_INT (0)Start timeoutMISSION_ITEM_INT (0)MISSION_REQUEST_INT (1)Start timeoutMISSION_ITEM_INT (1)MISSION_ACKGCSDrone

Note:

In more detail, the sequence of operations is:

  1. GCS (client) sends MISSION_COUNT including the number of mission items to be uploaded (count)
    • A timeout must be started for the GCS to wait on the response from Drone (MISSION_REQUEST_INT) .
  2. Drone (server) receives the message, and prepares to upload mission items.
  3. Drone responds with MISSION_REQUEST_INT requesting the mission number to upload (seq)
  4. GCS receives MISSION_REQUEST_INT and responds with the requested mission item in a MISSION_ITEM_INT message.
  5. Drone and GCS repeat the MISSION_REQUEST_INT/MISSION_ITEM_INT cycle until all items are uploaded.
  6. For the last mission item, the drone responds with MISSION_ACK with the result of the operation result: type (MAV_MISSION_RESULT):
  7. GCS receives MISSION_ACK:
    • If MAV_MISSION_ACCEPTED the operation is complete.
    • If an error, the transaction fails but may be retried.

Download a Mission from the Vehicle

The diagram below shows the communication sequence to download a mission from a drone (assuming all operations succeed).

GCSDroneMISSION_REQUEST_LISTStart timeoutMISSION_COUNTMISSION_REQUEST_INT (0)Start timeoutMISSION_ITEM_INT (0)MISSION_REQUEST_INT (1)Start timeoutMISSION_ITEM_INT (1)MISSION_ACKGCSDrone

The sequence shows the mission commands packaged in MISSION_ITEM_INT messages. Protocol implementations must also support MISSION_ITEM and MISSION_REQUEST in the same way (see MISSION_ITEM_INT vs MISSION_ITEM below).

The sequence is similar to that for uploading a mission. The main difference is that the client (e.g. GCS) sends MISSION_REQUEST_LIST, which triggers the autopilot to respond with the current count of items. This starts a cycle where the GCS requests mission items, and the drone supplies them.

Set Current Mission Item

The diagram below shows the communication sequence to set the current mission item.

GCSDroneMISSION_SET_CURRENTMISSION_CURRENTGCSDrone

Notes:

  • There is no specific timeout/resend on this message.
  • The acknowledgment of the message is via broadcast of mission/system status, which is not associated with the original message. This approach is used because the message is relevant to all mission-handling clients.

In more detail, the sequence of operations is:

  1. GCS (client) sends MISSION_SET_CURRENT, specifying the new sequence number (seq).
  2. Drone (server) receives message and attempts to update the current mission sequence number.
    • On success, the Drone should broadcast a MISSION_CURRENT message containing the current sequence number (seq).
    • On failure, the Drone should broadcast a STATUSTEXT with a MAV_SEVERITY and a string stating the problem. This may be displayed in the UI of receiving systems.

Monitor Mission Progress

GCS/developer API can monitor progress by handling the appropriate messages sent by the drone:

  • The vehicle (server) must broadcast a MISSION_ITEM_REACHED message whenever a new mission item is reached. The message contains the seq number of the current mission item.
  • The vehicle must also broadcast a MISSION_CURRENT message if the current mission item is changed by a message.

Clear Missions

The diagram below shows the communication sequence to clear the mission from a drone (timeouts are not displayed, and we assume all operations succeed).

GCSDroneMISSION_CLEAR_ALLStart timeoutMISSION_ACKGCSDrone

In more detail, the sequence of operations is:

  1. GCS (client) sends MISSION_CLEAR_ALL
    • A timeout is started for the GCS to wait on MISSION_ACK from Drone.
  2. Drone (server) receives the message, and clears the mission.
    • A mission is considered cleared if a subsequent requests for mission count or current mission item indicates that there is no mission uploaded.
  3. Drone responds with MISSION_ACK that includes the result type (MAV_MISSION_RESULT):
  4. GCS receives MISSION_ACK:
    • If MAV_MISSION_ACCEPTED the GCS clears its own stored information about the mission (that was just removed from the vehicle) and completes.
    • If an error, the transaction fails, and the GCS record of the mission (if any) is retained.
  5. If no MISSION_ACK is received the operation will eventually timeout and may be retried (see above).

Timeouts and Retries

All the client (GCS) commands are sent with a timeout. If a MISSION_ACK is not received before the timeout then the client (GCS) may resend the message. If no response is received after a number of retries then the client must cancel the operation and return to an idle state.

The recommended timeout values before resending, and the number of retries are:

  • Timeout (default): 1500 ms
  • Timeout (mission items): 250 ms.
  • Retries (max): 5

MISSION_ITEM_INT vs MISSION_ITEM

The operations/sequence diagrams above show the message commands being requested/sent using MISSION_REQUEST_INT and MISSION_ITEM_INT.

Protocol implementations must also support the same operations/sequences using the corresponding MISSION_REQUEST and MISSION_ITEM message types. The only difference is that MISSION_ITEM_INT encodes the latitude and longitude as integers rather than floats.

MAVLink users should always prefer the *_INT variants. These avoid/reduce the precision limitations from using MISSION_ITEM.

Mission File Formats

Ground stations and developer APIs commonly support higher level APIs for uploading and downloading missions in files. The commonly supported file formats are listed below.

JSON File Format (standard)

The standard file format for missions is JSON, as implemented in the QGroundControl reference implementation. The JSON file format has additional meta data which is not serialized over the link. The JSON file below shows an example mission with two waypoints.

{
    "fileType": "Plan",
    "geoFence": {
        "polygon": [
        ],
        "version": 1
    },
    "groundStation": "QGroundControl",
    "mission": {
        "cruiseSpeed": 16,
        "firmwareType": 12,
        "hoverSpeed": 4,
        "items": [
            {
                "autoContinue": true,
                "command": 22,
                "coordinate": [
                    47.385913889999998,
                    8.5520674900000007,
                    15
                ],
                "doJumpId": 1,
                "frame": 3,
                "params": [
                    0,
                    0,
                    0,
                    null
                ],
                "type": "SimpleItem"
            },
            {
                "autoContinue": true,
                "command": 16,
                "coordinate": [
                    47.383052030000002,
                    8.5556602700000006,
                    15
                ],
                "doJumpId": 2,
                "frame": 3,
                "params": [
                    0,
                    0,
                    0,
                    null
                ],
                "type": "SimpleItem"
            }
        ],
        "plannedHomePosition": [
            47.386183686176871,
            8.5520674900000007,
            15
        ],
        "vehicleType": 2,
        "version": 2
    },
    "rallyPoints": {
        "points": [
        ],
        "version": 1
    },
    "version": 1
}

Plain Text File Format

Additionally, QGroundControl and many other GCS support a non-standard plain-text format for missions. This is not officially part of MAVLink.

The format is shown below. Note that the spaces between the numbers/fields are actually <tab> (Use \t in most programming languages):

QGC WPL <VERSION>
<INDEX> <CURRENT WP> <COORD FRAME> <COMMAND> <PARAM1> <PARAM2> <PARAM3> <PARAM4> <PARAM5/X/LONGITUDE> <PARAM6/Y/LATITUDE> <PARAM7/Z/ALTITUDE> <AUTOCONTINUE>
Example
QGC WPL 110
0    1    0    16    0.149999999999999994    0    0    0    8.54800000000000004    47.3759999999999977    550    1
1    0    0    16    0.149999999999999994    0    0    0    8.54800000000000004    47.3759999999999977    550    1
2    0    0    16    0.149999999999999994    0    0    0    8.54800000000000004    47.3759999999999977    550    1

C Implementation

The protocol has been implemented in C by PX4 and QGroundControl.
This implementation can be used in your own code within the terms of their software licenses.

PX4 Implementation:

QGroundControl* implementation:

ArduPilot

  • TBD

results matching ""

    No results matching ""