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.
  • MAVLink commands that are common to most autopilots/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 2 supports three types of "missions": flight plans, geofences and rally/safe points. The protocol uses the same sequence of operations for all types (albeit with different types of Mission Items). The mission types must be stored and handled separately/independently.

Mission protocol messages include the type of associated mission in the mission_type field (a MAVLink 2 message extension). The field takes one of the MAV_MISSION_TYPE enum values: MAV_MISSION_TYPE_MISSION, MAV_MISSION_TYPE_FENCE, MAV_MISSION_TYPE_RALLY.

MAVLink 1 supports only "regular" flight-plan missions (this is implied/not explicitly set).

Mission items for all the mission types are defined in the MAV_CMD enum.

MAV_CMD is used to define commands that can be used in missions ("mission items") and commands that can be sent outside of a mission context (using the Command Protocol). Some MAV_CMD can be used with both mission and command protocols. Not all commands/mission items are supported on all systems (or for all flight modes).

The items for the different types of mission are identified using a simple name prefix convention:

The commands are transmitted/encoded in MISSION_ITEM or MISSION_ITEM_INT messages. These messages include fields to identify the desired mission item (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 message.
frameuint8_tMAV_FRAMEThe coordinate system of the waypoint.
ArduPilot and PX4 both only support global frames in MAVLink 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.

Message/Enum Summary

The following messages and enums are used by the service.

MessageDescription
MISSION_REQUEST_LISTInitiate mission download from a system by requesting the list of mission items.
MISSION_COUNTSend the number of items in a mission. This is used to initiate mission upload or as a response to MISSION_REQUEST_LIST when [downloading a mission].
MISSION_REQUEST_INTRequest mission item data for a specific sequence number be sent by the recipient using a MISSION_ITEM_INT message. Used for mission upload and download.
MISSION_REQUESTRequest mission item data for a specific sequence number be sent by the recipient using a MISSION_ITEM message. Used for mission upload and download.
MISSION_ITEM_INTMessage encoding a mission item/command (defined in a MAV_CMD). The message encodes positional information in integer parameters for greater precision than MISSION_ITEM. Used for mission upload and [download].
MISSION_ITEMMessage encoding a mission item/command (defined in a MAV_CMD). The message encodes positional information in float parameters. Used for mission upload and download.
MISSION_ACKAcknowledgment message when a system completes a mission operation (e.g. sent by autopilot after it has uploaded all mission items). The message includes a MAV_MISSION_RESULT indicating either success or the type of failure.
MISSION_CURRENTMessage containing the current mission item sequence number. This is emitted when the current mission item is set/changed.
MISSION_SET_CURRENTSet the current mission item by sequence number (continue to this item on the shortest path).
STATUSTEXTSent to notify systems when a request to set the current mission item fails.
MISSION_CLEAR_ALLMessage sent to clear/delete all mission items stored on a system.
MISSION_ITEM_REACHEDMessage emitted by system whenever it reaches a new waypoint. Used to monitor progress.
MISSION_REQUEST_PARTIAL_LISTInitiate a partial download of mission items from a system/component.
MISSION_WRITE_PARTIAL_LISTInitiate a partial upload of new mission items to a system/component.
EnumDescription
MAV_MISSION_TYPEMission type for message (mission, geofence, rallypoints).
MAV_MISSION_RESULTUsed to indicate the success or failure reason for an operation (e.g. to upload or download a mission). This is carried in a MISSION_ACK.
MAV_FRAMECo-ordinate frame for position/velocity/acceleration data in the message.
MAV_CMDMission Items (and MAVLink commands). These can be sent in MISSION_ITEM or MISSION_ITEM_INT.

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 (1)Start timeoutMISSION_ITEM_INT (1)MISSION_REQUEST_INT (2)Start timeoutMISSION_ITEM_INT (2)MISSION_ACKGCSDrone

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 first mission item (seq==1).
  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, iterating seq 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.

Note:

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 (1)Start timeoutMISSION_ITEM_INT (1)MISSION_REQUEST_INT (2)Start timeoutMISSION_ITEM_INT (2)MISSION_ACKGCSDrone

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.

The sequence shows the MAVLink 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).

Set Current Mission Item

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

GCSDroneMISSION_SET_CURRENTMISSION_CURRENTGCSDrone

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.

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.

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).

Upload Partial Mission

TBD

Download Partial Mission

TBD

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

The defacto standard file format for exchanging missions/plans is discussed in: File Formats > Mission Plain-Text File Format.

Implementations

PX4

The protocol has been implemented in C.

Source code:

The implementation status is (at time of writing):

  • Flight plan missions:
    • upload, download, clearing missions, and monitoring progress are supported as defined in this specification.
    • partial upload and partial download are not supported.
  • Geofence missions" are supported as defined in this specification.
  • Rally point "missions" are not supported on PX4.

QGroundControl

The protocol has been implemented in C++.

Source code:

ArduPilot

ArduPilot implements the mission protocol in C++.

ArduPilot uses the same messages and message flow described in this specification. There are some implementation diferences that affect compatibility. These are documented below.

Source:

Flight Plan Missions

Mission upload, download, clearing missions, and monitoring progress and partial mission upload (MISSION_WRITE_PARTIAL_LIST) are supported.

Partial mission download is not supported (MISSION_REQUEST_PARTIAL_LIST).

ArduPilot's implementation differs from this specification (non-exhaustively):

  • The first mission sequence number (seq==0) is populated with the home position of the vehicle instead of the first mission item.
  • Mission uploads are not "atomic". An upload that fails (or is canceled) part-way through will not match the pre-update state. Instead it may be a mix of the original and new mission.
  • Even if upload is successful, the vehicle mission may not match the version on the uploading system (and if the mission is then downloaded it will differ from the original).
    • If you try and upload more items than ArduPilot can store the system will "accept" the items (i.e. not report a failure) but will just overwrite each new item to the same (highest) slot in the mission list.
    • Only fields that are used are stored.
    • There is rounding on some fields (and in some cases internal maximum possible values due to available storage space). Failures can occur if you do a straight comparison of the float params before/after upload.
  • A MISSION_ACK returning an error value (NACK) does not terminate the upload (i.e. it is not considered an unrecoverable error). As long as ArduPilot has not yet timed-out a system can retry the current mission item upload.
  • A mission cannot be cleared while it is being executed (i.e. while in Auto mode). Note that a new mission can be uploaded (even a zero-size mission - which is equivalent to clearing).
  • Explicit cancellation of operations is not supported. If one end stops communicating the other end will eventually timeout and reset itself to an idle/ready state.

The following behaviour is not defined by the specification (but is still of interest):

  • ArduPilot performs some validation of fields when mission items are submitted. The validation code is common to all vehicles; mission items that are not understood by the vehicle type are accepted on upload but skipped during mission execution.
  • ArduPilot preforms some vehicle-specific validation at mission runtime (e.g. of jump targets).
  • A new mission can be uploaded while a mission is being executed. In this case the current waypoint will be executed to completion even if the waypoint sequence is different in the new mission (to get the new item you would need to reset the sequence or switch in/out of auto mode).
  • ArduPilot missions are not stored in an SD card and therefore have a vehicle/board-specific maximum mission size (as a benefit, on ArduPilot, missions can survive SD card failure in flight).

Geofence Missions

Geofence is supported by ArduPilot, but are not managed using this protocol.

Rally Point Missions

Rally points are supported by ArduPilot, but are not managed using this protocol

MAVSDK

TBD

DroneKit

TBD

results matching ""

    No results matching ""