Command Protocol

The MAVLink command protocol allows guaranteed delivery of MAVLink commands.

Commands are values of MAV_CMD that define the values of up to 7 parameters. These parameters and the command id are encoded in COMMAND_INT or COMMAND_LONG for sending.

The protocol provides reliable delivery by expecting a matching acknowledgement (COMMAND_ACK) from commands to indicate command arrival, and result. If no acknowledgement is received the command must be automatically re-sent.

COMMAND_INT is generally recommended when sending positional information as it allows greater precision, and is explicit about the co-ordinate frame. Commands that require float-only properties in parameters 5, 6 must be sent in COMMAND_LONG (e.g. commands where NaN has an explicit meaning).

Message/Enum Summary

MessageDescription
COMMAND_INTMessage for encoding a command (MAV_CMD). The message encodes commands into up to 7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers. The scaled integers are used for positional information (scaling depends on the actual command value). The coordinate frame of positional parameters is explicitly specified in a frame field. Commands that require float-only properties in parameters 5, 6 cannot be sent in this message (e.g. commands where NaN has an explicit meaning).
COMMAND_LONGMessage for encoding a command (MAV_CMD). The mesage encodes commands into up to 7 float parameters. The coordinate frame used for positional co-ordinates is implementation dependent. Any command may be packaged in this message, but there may be some loss of precision for positional co-ordinates (latitude, longitude).
COMMAND_ACKCommand acknowledgement. Includes result (success, failure, still in progress) and may include progress information and additional detail about failure reasons.
COMMAND_CANCELCancel a long running command.
EnumDescription
MAV_CMDCommands to be executed/sent in the command messages.
MAV_FRAMECoordinate frame. Used in COMMAND_INT to specify the co-ordinate frame of any positional parameters.
MAV_RESULTResult of command, included in COMMAND_ACK.result.

Sequences

Mermaid Sequence: Command Long

If the command drops the sender should increase the confirmation field:

Mermaid Sequence: increase confirmation field

Long Running Commands

Some commands are long running, and cannot complete immediately. The drone reports its progress by sending COMMMAND_ACK messages with COMMAND_ACK.result=MAV_RESULT_IN_PROGRESS and the progress as a percentage in COMMMAND_ACK.progress ([0-100] percent complete, 255 if progress not supplied). When the operation completes, the drone must terminate with a COMMMAND_ACK containing the final result of the operation: MAV_RESULT_ACCEPTED, MAV_RESULT_FAILED, MAV_RESULT_CANCELLED).

Mermaid Sequence: MAV_RESULT_IN_PROGRESS

Long running operations may be cancelled by sending the COMMAND_CANCEL message. The drone should cancel the operation and complete the sequence by sending COMMAND_ACK with COMMAND_ACK.result=MAV_RESULT_CANCELLED

  • If cancellation is not supported the drone can just continue to send progress updates until completion.
  • If the sequence has already completed (or is idle) the cancel command should be ignored.

The rate at which progress messages are emitted is system-dependent. Generally though, the GCS should have a much increased timeout after receiving an ACK with MAV_RESULT_IN_PROGRESS.

If a timeout is triggered when waiting for a progress or completion update, the GCS should terminate the sequence (return to the idle state) and notify the user if appropriate.

Only one instance of a particular long running command can execute at a time; to restart a long running operation (i.e. with new parameters) it must first be cancelled! If the same command is recieved while the operation is in progress the new command should be ACKed with MAV_RESULT_TEMPORARILY_REJECTED (to indicate that the target is busy).

The protocol allows for different long running commands to run in parallel, if supported by the state machine of the recieving flight stack. If a flight stack does not support multiple commands running in parallel it should ACK new commands with MAV_RESULT_TEMPORARILY_REJECTED (with the possible exception of the COMMAND_CANCEL, which might be used to cancel the first request).

results matching ""

    No results matching ""