Dialect: development

This dialect contains messages that are proposed for inclusion in the standard set, in order to ease development of prototype implementations. They should be considered a 'work in progress' and not included in production builds.

This topic is a human-readable form of the XML definition file: development.xml.

MAVLink 2 messages have an ID > 255 and are marked up using (MAVLink 2) in their description.

MAVLink 2 extension fields that have been added to MAVLink 1 messages are displayed in blue.

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.

MAVLink Type Enumerations

WIFI_NETWORK_SECURITY

[Enum] WiFi wireless security protocols.

ValueField NameDescription
0WIFI_NETWORK_SECURITY_UNDEFINEDUndefined or unknown security protocol.
1WIFI_NETWORK_SECURITY_OPENOpen network, no security.
2WIFI_NETWORK_SECURITY_WEPWEP.
3WIFI_NETWORK_SECURITY_WPA1WPA1.
4WIFI_NETWORK_SECURITY_WPA2WPA2.
5WIFI_NETWORK_SECURITY_WPA3WPA3.

AIRSPEED_SENSOR_TYPE

[Enum] Types of airspeed sensor/data. May be be used in AIRSPEED message to estimate accuracy of indicated speed.

ValueField NameDescription
0AIRSPEED_SENSOR_TYPE_UNKNOWNAirspeed sensor type unknown/not supplied.
1AIRSPEED_SENSOR_TYPE_DIFFERENTIALDifferential airspeed sensor
2AIRSPEED_SENSOR_TYPE_MASS_FLOWMass-flow airspeed sensor.
3AIRSPEED_SENSOR_TYPE_WINDVANEWindvane airspeed sensor.
4AIRSPEED_SENSOR_TYPE_SYNTHETICSynthetic/calculated airspeed.

PARAM_TRANSACTION_TRANSPORT

[Enum] Possible transport layers to set and get parameters via mavlink during a parameter transaction.

ValueField NameDescription
0PARAM_TRANSACTION_TRANSPORT_PARAMTransaction over param transport.
1PARAM_TRANSACTION_TRANSPORT_PARAM_EXTTransaction over param_ext transport.

PARAM_TRANSACTION_ACTION

[Enum] Possible parameter transaction actions.

ValueField NameDescription
0PARAM_TRANSACTION_ACTION_STARTCommit the current parameter transaction.
1PARAM_TRANSACTION_ACTION_COMMITCommit the current parameter transaction.
2PARAM_TRANSACTION_ACTION_CANCELCancel the current parameter transaction.

MAVLink Commands (MAV_CMD)

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

MAV_CMD_PARAM_TRANSACTION (900 )

[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)DescriptionValues
1: ActionAction to be performed (start, commit, cancel, etc.)PARAM_TRANSACTION_ACTION
2: TransportPossible transport layers to set and get parameters via mavlink during a parameter transaction.PARAM_TRANSACTION_TRANSPORT
3: Transaction IDIdentifier for a specific transaction.

MAV_CMD_SET_FENCE_BREACH_ACTION (5010 )

[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)DescriptionValues
1: ActionFence action on breach.FENCE_ACTION

MAV_CMD_DO_UPGRADE (247 )

[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)DescriptionValues
1: Component IDComponent id of the component to be upgraded. If set to 0, all components should be upgraded.MAV_COMPONENT
2: Reboot0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.min:0 max:1 increment:1
3Reserved
4Reserved
5Reserved
6Reserved
7WIP: upgrade progress report rate (can be used for more granular control).

MAV_CMD_GROUP_START (301 )

[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)DescriptionValues
1: Group IDMission-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

MAV_CMD_GROUP_END (302 )

[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)DescriptionValues
1: Group IDMission-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

MAVLink Messages

PARAM_ACK_TRANSACTION ( #19 )

[Message] Response from a PARAM_SET message when it is used in a transaction.

Field NameTypeValuesDescription
target_systemuint8_tId of system that sent PARAM_SET message.
target_componentuint8_tId of system that sent PARAM_SET message.
param_idchar[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_valuefloatParameter value (new value if PARAM_ACCEPTED, current value otherwise)
param_typeuint8_tMAV_PARAM_TYPEParameter type.
param_resultuint8_tPARAM_ACKResult code.

MISSION_CHANGED ( #52 )

[Message] A broadcast message to notify any ground station or SDK if a mission, geofence or safe points have changed on the vehicle.

Field NameTypeValuesDescription
start_indexint16_tStart index for partial mission change (-1 for all items).
end_indexint16_tEnd 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_sysiduint8_tSystem ID of the author of the new mission.
origin_compiduint8_tMAV_COMPONENTCompnent ID of the author of the new mission.
mission_typeuint8_tMAV_MISSION_TYPEMission type.

MISSION_CHECKSUM ( #53 )

[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 NameTypeValuesDescription
mission_typeuint8_tMAV_MISSION_TYPEMission type.
checksumuint32_tCRC32 checksum of current plan for specified type.

AIRSPEED ( #295 )

[Message] (MAVLink 2) Airspeed information from a sensor.

Field NameTypeUnitsValuesDescription
iduint8_tSensor ID.
airspeedfloatm/sCalibrated airspeed (CAS) if available, otherwise indicated airspeed (IAS).
temperatureint16_tcdegCTemperature. INT16_MAX for value unknown/not supplied.
press_difffloathPaDifferential pressure. NaN for value unknown/not supplied.
press_staticfloathPaStatic pressure. NaN for value unknown/not supplied.
errorfloatm/sError/accuracy. NaN for value unknown/not supplied.
typeuint8_tAIRSPEED_SENSOR_TYPEAirspeed sensor type. NaN for value unknown/not supplied. Used to estimate accuracy (i.e. as an alternative to using the error field).

WIFI_NETWORK_INFO ( #298 )

[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 NameTypeUnitsValuesDescription
ssidchar[32]Name of Wi-Fi network (SSID).
channel_iduint8_tWiFi network operating channel ID. Set to 0 if unknown or unidentified.
signal_qualityuint8_t%WiFi network signal quality.
data_rateuint16_tMiB/sWiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
securityuint8_tWIFI_NETWORK_SECURITYWiFi network security type.

GROUP_START ( #414 )

[Message] (MAVLink 2) Emitted during mission execution when control reaches MAV_CMD_GROUP_START.

Field NameTypeUnitsDescription
group_iduint32_tMission-unique group id (from MAV_CMD_GROUP_START).
mission_checksumuint32_tCRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
time_usecuint64_tusTimestamp (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.

GROUP_END ( #415 )

[Message] (MAVLink 2) Emitted during mission execution when control reaches MAV_CMD_GROUP_END.

Field NameTypeUnitsDescription
group_iduint32_tMission-unique group id (from MAV_CMD_GROUP_END).
mission_checksumuint32_tCRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
time_usecuint64_tusTimestamp (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.

results matching ""

    No results matching ""