MAVLink Include Files: standard.xml
The current MAVLink version is 2.0. The minor version numbers (after the dot) range from 1-255.
This file has protocol dialect: 0.
[Enum] WiFi wireless security protocols.
| Value | Field Name | Description |
|---|---|---|
| 0 | WIFI_NETWORK_SECURITY_UNDEFINED | Undefined or unknown security protocol. |
| 1 | WIFI_NETWORK_SECURITY_OPEN | Open network, no security. |
| 2 | WIFI_NETWORK_SECURITY_WEP | WEP. |
| 3 | WIFI_NETWORK_SECURITY_WPA1 | WPA1. |
| 4 | WIFI_NETWORK_SECURITY_WPA2 | WPA2. |
| 5 | WIFI_NETWORK_SECURITY_WPA3 | WPA3. |
[Enum] Types of airspeed sensor/data. May be be used in AIRSPEED message to estimate accuracy of indicated speed.
| Value | Field Name | Description |
|---|---|---|
| 0 | AIRSPEED_SENSOR_TYPE_UNKNOWN | Airspeed sensor type unknown/not supplied. |
| 1 | AIRSPEED_SENSOR_TYPE_DIFFERENTIAL | Differential airspeed sensor |
| 2 | AIRSPEED_SENSOR_TYPE_MASS_FLOW | Mass-flow airspeed sensor. |
| 3 | AIRSPEED_SENSOR_TYPE_WINDVANE | Windvane airspeed sensor. |
| 4 | AIRSPEED_SENSOR_TYPE_SYNTHETIC | Synthetic/calculated airspeed. |
[Enum] Possible transport layers to set and get parameters via mavlink during a parameter transaction.
| Value | Field Name | Description |
|---|---|---|
| 0 | PARAM_TRANSACTION_TRANSPORT_PARAM | Transaction over param transport. |
| 1 | PARAM_TRANSACTION_TRANSPORT_PARAM_EXT | Transaction over param_ext transport. |
[Enum] Possible parameter transaction actions.
| Value | Field Name | Description |
|---|---|---|
| 0 | PARAM_TRANSACTION_ACTION_START | Commit the current parameter transaction. |
| 1 | PARAM_TRANSACTION_ACTION_COMMIT | Commit the current parameter transaction. |
| 2 | PARAM_TRANSACTION_ACTION_CANCEL | Cancel the current parameter transaction. |
MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.
Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries
[Command] Request to start or end a parameter transaction. Multiple kinds of transport layers can be used to exchange parameters in the transaction (param, param_ext and mavftp). The command response can either be a success/failure or an in progress in case the receiving side takes some time to apply the parameters.
| Param (:Label) | Description | Values |
|---|---|---|
| 1: Action | Action to be performed (start, commit, cancel, etc.) | PARAM_TRANSACTION_ACTION |
| 2: Transport | Possible transport layers to set and get parameters via mavlink during a parameter transaction. | PARAM_TRANSACTION_TRANSPORT |
| 3: Transaction ID | Identifier for a specific transaction. |
[Command] Sets the action on geofence breach. If sent using the command protocol this sets the system-default geofence action. As part of a mission protocol plan it sets the fence action for the next complete geofence definition *after* the command. Note: A fence action defined in a plan will override the default system setting (even if the system-default is `FENCE_ACTION_NONE`). Note: Every geofence in a plan can have its own action; if no fence action is defined for a particular fence the system-default will be used. Note: The flight stack should reject a plan or command that uses a geofence action that it does not support and send a STATUSTEXT with the reason.
| Param (:Label) | Description | Values |
|---|---|---|
| 1: Action | Fence action on breach. | FENCE_ACTION |
[Command] Request a target system to start an upgrade of one (or all) of its components. For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. The system doing the upgrade will report progress using the normal command protocol sequence for a long running operation. Command protocol information: https://mavlink.io/en/services/command.html.
| Param (:Label) | Description | Values |
|---|---|---|
| 1: Component ID | Component id of the component to be upgraded. If set to 0, all components should be upgraded. | MAV_COMPONENT |
| 2: Reboot | 0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed. | min:0 max:1 increment:1 |
| 3 | Reserved | |
| 4 | Reserved | |
| 5 | Reserved | |
| 6 | Reserved | |
| 7 | WIP: upgrade progress report rate (can be used for more granular control). |
[Command] Define start of a group of mission items. When control reaches this command a GROUP_START message is emitted. The end of a group is marked using MAV_CMD_GROUP_END with the same group id. Group ids are expected, but not required, to iterate sequentially. Groups can be nested.
| Param (:Label) | Description | Values |
|---|---|---|
| 1: Group ID | Mission-unique group id. Group id is limited because only 24 bit integer can be stored in 32 bit float. | min:0 max:16777216 increment:1 |
[Command] Define end of a group of mission items. When control reaches this command a GROUP_END message is emitted. The start of the group is marked is marked using MAV_CMD_GROUP_START with the same group id. Group ids are expected, but not required, to iterate sequentially. Groups can be nested.
| Param (:Label) | Description | Values |
|---|---|---|
| 1: Group ID | Mission-unique group id. Group id is limited because only 24 bit integer can be stored in 32 bit float. | min:0 max:16777216 increment:1 |
[Message] Response from a PARAM_SET message when it is used in a transaction.
| Field Name | Type | Values | Description |
|---|---|---|---|
| target_system | uint8_t | Id of system that sent PARAM_SET message. | |
| target_component | uint8_t | Id of system that sent PARAM_SET message. | |
| param_id | char[16] | Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string | |
| param_value | float | Parameter value (new value if PARAM_ACCEPTED, current value otherwise) | |
| param_type | uint8_t | MAV_PARAM_TYPE | Parameter type. |
| param_result | uint8_t | PARAM_ACK | Result code. |
[Message] A broadcast message to notify any ground station or SDK if a mission, geofence or safe points have changed on the vehicle.
| Field Name | Type | Values | Description |
|---|---|---|---|
| start_index | int16_t | Start index for partial mission change (-1 for all items). | |
| end_index | int16_t | End index of a partial mission change. -1 is a synonym for the last mission item (i.e. selects all items from start_index). Ignore field if start_index=-1. | |
| origin_sysid | uint8_t | System ID of the author of the new mission. | |
| origin_compid | uint8_t | MAV_COMPONENT | Compnent ID of the author of the new mission. |
| mission_type | uint8_t | MAV_MISSION_TYPE | Mission type. |
[Message] Checksum for the current mission, rally point or geofence plan, or for the "combined" plan (a GCS can use these checksums to determine if it has matching plans). This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition (immediately after the MISSION_ACK that completes the upload sequence). It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required. The checksum must be calculated on the autopilot, but may also be calculated by the GCS. The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation). The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order): frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7. The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point.
| Field Name | Type | Values | Description |
|---|---|---|---|
| mission_type | uint8_t | MAV_MISSION_TYPE | Mission type. |
| checksum | uint32_t | CRC32 checksum of current plan for specified type. |
[Message] (MAVLink 2) Airspeed information from a sensor.
| Field Name | Type | Units | Values | Description |
|---|---|---|---|---|
| id | uint8_t | Sensor ID. | ||
| airspeed | float | m/s | Calibrated airspeed (CAS) if available, otherwise indicated airspeed (IAS). | |
| temperature | int16_t | cdegC | Temperature. INT16_MAX for value unknown/not supplied. | |
| press_diff | float | hPa | Differential pressure. NaN for value unknown/not supplied. | |
| press_static | float | hPa | Static pressure. NaN for value unknown/not supplied. | |
| error | float | m/s | Error/accuracy. NaN for value unknown/not supplied. | |
| type | uint8_t | AIRSPEED_SENSOR_TYPE | Airspeed sensor type. NaN for value unknown/not supplied. Used to estimate accuracy (i.e. as an alternative to using the error field). |
[Message] (MAVLink 2) Detected WiFi network status information. This message is sent per each WiFi network detected in range with known SSID and general status parameters.
| Field Name | Type | Units | Values | Description |
|---|---|---|---|---|
| ssid | char[32] | Name of Wi-Fi network (SSID). | ||
| channel_id | uint8_t | WiFi network operating channel ID. Set to 0 if unknown or unidentified. | ||
| signal_quality | uint8_t | % | WiFi network signal quality. | |
| data_rate | uint16_t | MiB/s | WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied. | |
| security | uint8_t | WIFI_NETWORK_SECURITY | WiFi network security type. |
[Message] (MAVLink 2) Basic component information data.
| Field Name | Type | Units | Values | Description |
|---|---|---|---|---|
| time_boot_ms | uint32_t | ms | Timestamp (time since system boot). | |
| vendor_name | uint8_t[32] | Name of the component vendor | ||
| model_name | uint8_t[32] | Name of the component model | ||
| software_version | char[24] | Sofware version. The version format can be custom, recommended is SEMVER 'major.minor.patch'. | ||
| hardware_version | char[24] | Hardware version. The version format can be custom, recommended is SEMVER 'major.minor.patch'. | ||
| capabilities | uint64_t | MAV_PROTOCOL_CAPABILITY | Component capability flags |
[Message] (MAVLink 2) Emitted during mission execution when control reaches MAV_CMD_GROUP_START.
| Field Name | Type | Units | Description |
|---|---|---|---|
| group_id | uint32_t | Mission-unique group id (from MAV_CMD_GROUP_START). | |
| mission_checksum | uint32_t | CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message. | |
| time_usec | uint64_t | us | Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. |
[Message] (MAVLink 2) Emitted during mission execution when control reaches MAV_CMD_GROUP_END.
| Field Name | Type | Units | Description |
|---|---|---|---|
| group_id | uint32_t | Mission-unique group id (from MAV_CMD_GROUP_END). | |
| mission_checksum | uint32_t | CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message. | |
| time_usec | uint64_t | us | Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number. |