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.

MAV_STANDARD_MODE

[Enum] Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. Modes may be set using MAV_CMD_DO_SET_STANDARD_MODE.

ValueField NameDescription
0MAV_STANDARD_MODE_NON_STANDARDNon standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode.
1MAV_STANDARD_MODE_POSITION_HOLDPosition mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process).
2MAV_STANDARD_MODE_ORBITOrbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process).
3MAV_STANDARD_MODE_CRUISECruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process).
4MAV_STANDARD_MODE_ALTITUDE_HOLDAltitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process).
5MAV_STANDARD_MODE_RETURN_HOMEReturn home mode (auto). Automatic mode that returns vehicle to home via a safe flight path. It may also automatically land the vehicle (i.e. RTL). The precise flight path and landing behaviour depend on vehicle configuration and type.
6MAV_STANDARD_MODE_SAFE_RECOVERYSafe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path (rally point or mission defined landing) . It may also automatically land the vehicle. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type.
7MAV_STANDARD_MODE_MISSIONMission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled.
8MAV_STANDARD_MODE_LANDLand mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type.
9MAV_STANDARD_MODE_TAKEOFFTakeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type.

MAV_BATTERY_STATUS_FLAGS

[Enum] Battery status flags for fault, health and state indication.

ValueField NameDescription
1MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USEThe battery is not ready to use (fly). Set if the battery has faults or other conditions that make it unsafe to fly with. Note: It will be the logical OR of other status bits (chosen by the manufacturer/integrator).
2MAV_BATTERY_STATUS_FLAGS_CHARGINGBattery is charging.
4MAV_BATTERY_STATUS_FLAGS_CELL_BALANCINGBattery is cell balancing (during charging). Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE may be set).
8MAV_BATTERY_STATUS_FLAGS_FAULT_CELL_IMBALANCEBattery cells are not balanced. Not ready to use.
16MAV_BATTERY_STATUS_FLAGS_AUTO_DISCHARGINGBattery is auto discharging (towards storage level). Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE would be set).
32MAV_BATTERY_STATUS_FLAGS_REQUIRES_SERVICEBattery requires service (not safe to fly). This is set at vendor discretion. It is likely to be set for most faults, and may also be set according to a maintenance schedule (such as age, or number of recharge cycles, etc.).
64MAV_BATTERY_STATUS_FLAGS_BAD_BATTERYBattery is faulty and cannot be repaired (not safe to fly). This is set at vendor discretion. The battery should be disposed of safely.
128MAV_BATTERY_STATUS_FLAGS_PROTECTIONS_ENABLEDAutomatic battery protection monitoring is enabled. When enabled, the system will monitor for certain kinds of faults, such as cells being over-voltage. If a fault is triggered then and protections are enabled then a safety fault (MAV_BATTERY_STATUS_FLAGS_FAULT_PROTECTION_SYSTEM) will be set and power from the battery will be stopped. Note that battery protection monitoring should only be enabled when the vehicle is landed. Once the vehicle is armed, or starts moving, the protections should be disabled to prevent false positives from disabling the output.
256MAV_BATTERY_STATUS_FLAGS_FAULT_PROTECTION_SYSTEMThe battery fault protection system had detected a fault and cut all power from the battery. This will only trigger if MAV_BATTERY_STATUS_FLAGS_PROTECTIONS_ENABLED is set. Other faults like MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_VOLT may also be set, indicating the cause of the protection fault.
512MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_VOLTOne or more cells are above their maximum voltage rating.
1024MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_VOLTOne or more cells are below their minimum voltage rating. A battery that had deep-discharged might be irrepairably damaged, and set both MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_VOLT and MAV_BATTERY_STATUS_FLAGS_BAD_BATTERY.
2048MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_TEMPERATUREOver-temperature fault.
4096MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_TEMPERATUREUnder-temperature fault.
8192MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_CURRENTOver-current fault.
16384MAV_BATTERY_STATUS_FLAGS_FAULT_SHORT_CIRCUITShort circuit event detected. The battery may or may not be safe to use (check other flags).
32768MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_VOLTAGEVoltage not compatible with power rail voltage (batteries on same power rail should have similar voltage).
65536MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_FIRMWAREBattery firmware is not compatible with current autopilot firmware.
131072MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_CELLS_CONFIGURATIONBattery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).
262144MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULLBattery capacity_consumed and capacity_remaining values are relative to a full battery (they sum to the total capacity of the battery). This flag would be set for a smart battery that can accurately determine its remaining charge across vehicle reboots and discharge/recharge cycles. If unset the capacity_consumed indicates the consumption since vehicle power-on, as measured using a power monitor. The capacity_remaining, if provided, indicates the estimated remaining capacity on the assumption that the battery was full on vehicle boot. If unset a GCS is recommended to advise that users fully charge the battery on power on.
4294967295MAV_BATTERY_STATUS_FLAGS_EXTENDEDReserved (not used). If set, this will indicate that an additional status field exists for higher status values.

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_DO_FIGURE_EIGHT (35 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Command] Fly a figure eight path as defined by the parameters. Set parameters to NaN/INT32_MAX (as appropriate) to use system-default values. The command is intended for fixed wing vehicles (and VTOL hybrids flying in fixed-wing mode), allowing POI tracking for gimbals that don't support infinite rotation. This command only defines the flight path. Speed should be set independently (use e.g. MAV_CMD_DO_CHANGE_SPEED). Yaw and other degrees of freedom are not specified, and will be flight-stack specific (on vehicles where they can be controlled independent of the heading).

Param (:Label)DescriptionUnits
1: Major RadiusMajor axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise. NaN: The radius will be set to 2.5 times the minor radius and direction is clockwise. Must be greater or equal to two times the minor radius for feasible values.m
2: Minor RadiusMinor axis radius of the figure eight. Defines the radius of the two circles that make up the figure. Negative value has no effect. NaN: The radius will be set to the default loiter radius.m
3Reserved (set to NaN)
4: OrientationOrientation of the figure eight major axis with respect to true north (range: [-pi,pi]). NaN: use default orientation aligned to true north.rad
5: Latitude/XCenter point latitude/X coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. INT32_MAX or NaN: Use current vehicle position, or current center if already loitering.
6: Longitude/YCenter point longitude/Y coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. INT32_MAX or NaN: Use current vehicle position, or current center if already loitering.
7: Altitude/ZCenter point altitude MSL/Z coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed. INT32_MAX or NaN: Use current vehicle altitude.

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

MAV_CMD_DO_SET_STANDARD_MODE (262 )

[Command] Enable the specified standard MAVLink mode. If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED.

Param (:Label)DescriptionValues
1: Standard ModeThe mode to set.MAV_STANDARD_MODE
2Reserved (set to 0)
3Reserved (set to 0)
4Reserved (set to 0)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

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

FIGURE_EIGHT_EXECUTION_STATUS ( #361 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) Vehicle status report that is sent out while figure eight execution is in progress (see MAV_CMD_DO_FIGURE_EIGHT). This may typically send at low rates: of the order of 2Hz.

Field NameTypeUnitsValuesDescription
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.
major_radiusfloatmMajor axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
minor_radiusfloatmMinor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
orientationfloatradOrientation of the figure eight major axis with respect to true north in [-pi,pi).
frameuint8_tMAV_FRAMEThe coordinate system of the fields: x, y, z.
xint32_tX coordinate of center point. Coordinate system depends on frame field.
yint32_tY coordinate of center point. Coordinate system depends on frame field.
zfloatmAltitude of center point. Coordinate system depends on frame field.

BATTERY_STATUS_V2 ( #369 )

[Message] (MAVLink 2) Battery dynamic information. This should be streamed (nominally at 1Hz). Static/invariant battery information is sent in SMART_BATTERY_INFO. Note that smart batteries should set the MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL bit to indicate that supplied capacity values are relative to a battery that is known to be full. Power monitors would not set this bit, indicating that capacity_consumed is relative to drone power-on, and that other values are estimated based on the assumption that the battery was full on power-on.

Field NameTypeUnitsValuesDescription
iduint8_tBattery ID
temperatureint16_tcdegCTemperature of the whole battery pack (not internal electronics). INT16_MAX field not provided.
voltagefloatVBattery voltage (total). NaN: field not provided.
currentfloatABattery current (through all cells/loads). Positive value when discharging and negative if charging. NaN: field not provided.
capacity_consumedfloatAhConsumed charge. NaN: field not provided. This is either the consumption since power-on or since the battery was full, depending on the value of MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL.
capacity_remainingfloatAhRemaining charge (until empty). UINT32_MAX: field not provided. Note: If MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL is unset, this value is based on the assumption the battery was full when the system was powered.
percent_remaininguint8_t%Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided.
status_flagsuint32_tMAV_BATTERY_STATUS_FLAGSFault, health, readiness, and other status indications.

COMPONENT_INFORMATION_BASIC ( #396 )

[Message] (MAVLink 2) Basic component information data.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
vendor_nameuint8_t[32]Name of the component vendor
model_nameuint8_t[32]Name of the component model
software_versionchar[24]Software version. The version format can be custom, recommended is SEMVER 'major.minor.patch'.
hardware_versionchar[24]Hardware version. The version format can be custom, recommended is SEMVER 'major.minor.patch'.
capabilitiesuint64_tMAV_PROTOCOL_CAPABILITYComponent capability flags

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.

AVAILABLE_MODES ( #435 )

[Message] (MAVLink 2) Get information about a particular flight modes. The message can be enumerated or requested for a particular mode using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each modes should only be emitted once (even if it is both standard and custom).

Field NameTypeValuesDescription
number_modesuint8_tThe total number of available modes for the current vehicle type.
mode_indexuint8_tThe current mode index within number_modes, indexed from 1.
standard_modeuint8_tMAV_STANDARD_MODEStandard mode.
base_modeuint8_tMAV_MODE_FLAGSystem mode bitmap.
custom_modeuint32_tA bitfield for use for autopilot-specific flags
mode_namechar[50]Name of custom mode, with null termination character. Should be omitted for standard modes.

CURRENT_MODE ( #436 )

[Message] (MAVLink 2) Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE.

Field NameTypeValuesDescription
standard_modeuint8_tMAV_STANDARD_MODEStandard mode.
base_modeuint8_tMAV_MODE_FLAGSystem mode bitmap.
custom_modeuint32_tA bitfield for use for autopilot-specific flags

results matching ""

    No results matching ""