data/method/mavlink/message_definitions/v1.0/development.xml

745 lines
57 KiB
XML
Raw Normal View History

2024-07-24 18:30:46 +08:00
<?xml version="1.0"?>
<mavlink>
<!-- XML file for prototyping definitions for common.xml -->
<include>common.xml</include>
<version>0</version>
<dialect>0</dialect>
<enums>
<enum name="WIFI_NETWORK_SECURITY">
<description>WiFi wireless security protocols.</description>
<entry value="0" name="WIFI_NETWORK_SECURITY_UNDEFINED">
<description>Undefined or unknown security protocol.</description>
</entry>
<entry value="1" name="WIFI_NETWORK_SECURITY_OPEN">
<description>Open network, no security.</description>
</entry>
<entry value="2" name="WIFI_NETWORK_SECURITY_WEP">
<description>WEP.</description>
</entry>
<entry value="3" name="WIFI_NETWORK_SECURITY_WPA1">
<description>WPA1.</description>
</entry>
<entry value="4" name="WIFI_NETWORK_SECURITY_WPA2">
<description>WPA2.</description>
</entry>
<entry value="5" name="WIFI_NETWORK_SECURITY_WPA3">
<description>WPA3.</description>
</entry>
</enum>
<enum name="AIRSPEED_SENSOR_FLAGS" bitmask="true">
<description>Airspeed sensor flags</description>
<entry value="0" name="AIRSPEED_SENSOR_UNHEALTHY">
<description>Airspeed sensor is unhealthy</description>
</entry>
<entry value="1" name="AIRSPEED_SENSOR_USING">
<description>True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.</description>
</entry>
</enum>
<!-- Transactions for parameter protocol -->
<enum name="PARAM_TRANSACTION_TRANSPORT">
<description>Possible transport layers to set and get parameters via mavlink during a parameter transaction.</description>
<entry value="0" name="PARAM_TRANSACTION_TRANSPORT_PARAM">
<description>Transaction over param transport.</description>
</entry>
<entry value="1" name="PARAM_TRANSACTION_TRANSPORT_PARAM_EXT">
<description>Transaction over param_ext transport.</description>
</entry>
</enum>
<enum name="PARAM_TRANSACTION_ACTION">
<description>Possible parameter transaction actions.</description>
<entry value="0" name="PARAM_TRANSACTION_ACTION_START">
<description>Commit the current parameter transaction.</description>
</entry>
<entry value="1" name="PARAM_TRANSACTION_ACTION_COMMIT">
<description>Commit the current parameter transaction.</description>
</entry>
<entry value="2" name="PARAM_TRANSACTION_ACTION_CANCEL">
<description>Cancel the current parameter transaction.</description>
</entry>
</enum>
<enum name="MAV_STANDARD_MODE">
<description>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.
</description>
<entry value="0" name="MAV_STANDARD_MODE_NON_STANDARD">
<description>Non standard mode.
This may be used when reporting the mode if the current flight mode is not a standard mode.
</description>
</entry>
<entry value="1" name="MAV_STANDARD_MODE_POSITION_HOLD">
<description>Position 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).
</description>
</entry>
<entry value="2" name="MAV_STANDARD_MODE_ORBIT">
<description>Orbit (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).
</description>
</entry>
<entry value="3" name="MAV_STANDARD_MODE_CRUISE">
<description>Cruise 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).
</description>
</entry>
<entry value="4" name="MAV_STANDARD_MODE_ALTITUDE_HOLD">
<description>Altitude 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).
</description>
</entry>
<entry value="5" name="MAV_STANDARD_MODE_RETURN_HOME">
<description>Return 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.
</description>
</entry>
<entry value="6" name="MAV_STANDARD_MODE_SAFE_RECOVERY">
<description>Safe 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.
</description>
</entry>
<entry value="7" name="MAV_STANDARD_MODE_MISSION">
<description>Mission mode (automatic).
Automatic mode that executes MAVLink missions.
Missions are executed from the current waypoint as soon as the mode is enabled.
</description>
</entry>
<entry value="8" name="MAV_STANDARD_MODE_LAND">
<description>Land mode (auto).
Automatic mode that lands the vehicle at the current location.
The precise landing behaviour depends on vehicle configuration and type.
</description>
</entry>
<entry value="9" name="MAV_STANDARD_MODE_TAKEOFF">
<description>Takeoff mode (auto).
Automatic takeoff mode.
The precise takeoff behaviour depends on vehicle configuration and type.
</description>
</entry>
</enum>
<enum name="MAV_MODE_PROPERTY" bitmask="true">
<description>Mode properties.
</description>
<entry value="1" name="MAV_MODE_PROPERTY_ADVANCED">
<description>If set, this mode is an advanced mode.
For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not.
A GCS can optionally use this flag to configure the UI for its intended users.
</description>
</entry>
<entry value="2" name="MAV_MODE_PROPERTY_NOT_USER_SELECTABLE">
<description>If set, this mode should not be added to the list of selectable modes.
The mode might still be selected by the FC directly (for example as part of a failsafe).
</description>
</entry>
</enum>
<enum name="MAV_BATTERY_STATUS_FLAGS" bitmask="true">
<description>Battery status flags for fault, health and state indication.</description>
<entry value="1" name="MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE">
<description>
The 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).
</description>
</entry>
<entry value="2" name="MAV_BATTERY_STATUS_FLAGS_CHARGING">
<description>
Battery is charging.
</description>
</entry>
<entry value="4" name="MAV_BATTERY_STATUS_FLAGS_CELL_BALANCING">
<description>
Battery is cell balancing (during charging).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE may be set).
</description>
</entry>
<entry value="8" name="MAV_BATTERY_STATUS_FLAGS_FAULT_CELL_IMBALANCE">
<description>
Battery cells are not balanced.
Not ready to use.
</description>
</entry>
<entry value="16" name="MAV_BATTERY_STATUS_FLAGS_AUTO_DISCHARGING">
<description>
Battery is auto discharging (towards storage level).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE would be set).
</description>
</entry>
<entry value="32" name="MAV_BATTERY_STATUS_FLAGS_REQUIRES_SERVICE">
<description>
Battery 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.).
</description>
</entry>
<entry value="64" name="MAV_BATTERY_STATUS_FLAGS_BAD_BATTERY">
<description>
Battery is faulty and cannot be repaired (not safe to fly).
This is set at vendor discretion.
The battery should be disposed of safely.
</description>
</entry>
<entry value="128" name="MAV_BATTERY_STATUS_FLAGS_PROTECTIONS_ENABLED">
<description>
Automatic 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.
</description>
</entry>
<entry value="256" name="MAV_BATTERY_STATUS_FLAGS_FAULT_PROTECTION_SYSTEM">
<description>
The 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.
</description>
</entry>
<entry value="512" name="MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_VOLT">
<description>One or more cells are above their maximum voltage rating.</description>
</entry>
<entry value="1024" name="MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_VOLT">
<description>
One 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.
</description>
</entry>
<entry value="2048" name="MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_TEMPERATURE">
<description>Over-temperature fault.</description>
</entry>
<entry value="4096" name="MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_TEMPERATURE">
<description>Under-temperature fault.</description>
</entry>
<entry value="8192" name="MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_CURRENT">
<description>Over-current fault.</description>
</entry>
<entry value="16384" name="MAV_BATTERY_STATUS_FLAGS_FAULT_SHORT_CIRCUIT">
<description>
Short circuit event detected.
The battery may or may not be safe to use (check other flags).
</description>
</entry>
<entry value="32768" name="MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_VOLTAGE">
<description>Voltage not compatible with power rail voltage (batteries on same power rail should have similar voltage).</description>
</entry>
<entry value="65536" name="MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_FIRMWARE">
<description>Battery firmware is not compatible with current autopilot firmware.</description>
</entry>
<entry value="131072" name="MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION">
<description>Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).</description>
</entry>
<entry value="262144" name="MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL">
<description>
Battery 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.
</description>
</entry>
<entry value="4294967295" name="MAV_BATTERY_STATUS_FLAGS_EXTENDED">
<description>Reserved (not used). If set, this will indicate that an additional status field exists for higher status values.</description>
</entry>
</enum>
<!-- The MAV_CMD enum entries describe either: -->
<!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) -->
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
<!-- ALL the entries in the MAV_CMD enum have a maximum of 7 parameters -->
<enum name="MAV_CMD">
<description>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</description>
<entry value="35" name="MAV_CMD_DO_FIGURE_EIGHT" hasLocation="true" isDestination="true">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>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).
</description>
<param index="1" label="Major Radius" units="m">Major 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.</param>
<param index="2" label="Minor Radius" units="m">Minor 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.</param>
<param index="3" reserved="true" default="NaN"/>
<param index="4" label="Orientation" units="rad">Orientation of the figure eight major axis with respect to true north (range: [-pi,pi]). NaN: use default orientation aligned to true north.</param>
<param index="5" label="Latitude/X">Center 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.</param>
<param index="6" label="Longitude/Y">Center 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.</param>
<param index="7" label="Altitude/Z">Center 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.</param>
</entry>
<entry value="900" name="MAV_CMD_PARAM_TRANSACTION" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Action" enum="PARAM_TRANSACTION_ACTION">Action to be performed (start, commit, cancel, etc.)</param>
<param index="2" label="Transport" enum="PARAM_TRANSACTION_TRANSPORT">Possible transport layers to set and get parameters via mavlink during a parameter transaction.</param>
<param index="3" label="Transaction ID">Identifier for a specific transaction.</param>
</entry>
<entry value="247" name="MAV_CMD_DO_UPGRADE" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Component ID" enum="MAV_COMPONENT">Component id of the component to be upgraded. If set to 0, all components should be upgraded.</param>
<param index="2" label="Reboot" minValue="0" maxValue="1" increment="1">0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Reserved</param>
<param index="6">Reserved</param>
<param index="7">WIP: upgrade progress report rate (can be used for more granular control).</param>
</entry>
<entry value="301" name="MAV_CMD_GROUP_START" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Group ID" minValue="0" maxValue="16777216" increment="1">Mission-unique group id.
Group id is limited because only 24 bit integer can be stored in 32 bit float.</param>
</entry>
<entry value="302" name="MAV_CMD_GROUP_END" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Group ID" minValue="0" maxValue="16777216" increment="1">Mission-unique group id.
Group id is limited because only 24 bit integer can be stored in 32 bit float.</param>
</entry>
<entry value="262" name="MAV_CMD_DO_SET_STANDARD_MODE" hasLocation="false" isDestination="false">
<description>Enable the specified standard MAVLink mode.
If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED.
</description>
<param index="1" label="Standard Mode" enum="MAV_STANDARD_MODE">The mode to set.</param>
<param index="2" reserved="true" default="0"/>
<param index="3" reserved="true" default="0"/>
<param index="4" reserved="true" default="0"/>
<param index="5" reserved="true" default="0"/>
<param index="6" reserved="true" default="0"/>
<param index="7" reserved="true" default="NaN"/>
</entry>
<entry value="550" name="MAV_CMD_SET_AT_S_PARAM" hasLocation="false" isDestination="false">
<description>Allows setting an AT S command of an SiK radio.
</description>
<param index="1" label="Radio instance">The radio instance, one-based, 0 for all.</param>
<param index="2" label="Index">The Sx index, e.g. 3 for S3 which is NETID.</param>
<param index="3" label="Value">The value to set it to, e.g. default 25 for NETID</param>
<param index="4" reserved="true"/>
<param index="5" reserved="true"/>
<param index="6" reserved="true"/>
<param index="7" reserved="true"/>
</entry>
<entry value="610" name="MAV_CMD_DO_SET_SYS_CMP_ID" hasLocation="false" isDestination="false">
<description>
Set system and component id.
This allows moving of a system and all its components to a new system id, or moving a particular component to a new system/component id.
Recipients must reject command addressed to broadcast system ID.
</description>
<param index="1" label="System ID" minValue="1" maxValue="255" increment="1">New system ID for target component(s). 0: ignore and reject command (broadcast system ID not allowed).</param>
<param index="2" label="Component ID" minValue="0" maxValue="255" increment="1">New component ID for target component(s). 0: ignore (component IDs don't change).</param>
<param index="3" label="Reboot">Reboot components after ID change. Any non-zero value triggers the reboot.</param>
<param index="4" reserved="true" default="NaN"/>
</entry>
<entry value="12900" name="MAV_CMD_ODID_SET_EMERGENCY" hasLocation="false" isDestination="false">
<description>Used to manually set/unset emergency status for remote id.
This is for compliance with MOC ASTM docs, specifically F358 section 7.7: "Emergency Status Indicator".
The requirement can also be satisfied by automatic setting of the emergency status by flight stack, and that approach is preferred.
See https://mavlink.io/en/services/opendroneid.html for more information.
</description>
<param index="1" label="Number" minValue="0" increment="1">Set/unset emergency 0: unset, 1: set</param>
<param index="2" reserved="true" default="NaN"/>
<param index="3" reserved="true" default="NaN"/>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="43004" name="MAV_CMD_EXTERNAL_WIND_ESTIMATE" hasLocation="false" isDestination="false">
<description>Set an external estimate of wind direction and speed.
This might be used to provide an initial wind estimate to the estimator (EKF) in the case where the vehicle is wind dead-reckoning, extending the time when operating without GPS before before position drift builds to an unsafe level. For this use case the command might reasonably be sent every few minutes when operating at altitude, and the value is cleared if the estimator resets itself.
</description>
<param index="1" label="Wind speed" units="m/s" minValue="0">Horizontal wind speed.</param>
<param index="2" label="Wind speed accuracy" units="m/s">Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown.</param>
<param index="3" label="Direction" units="deg" minValue="0" maxValue="360">Azimuth (relative to true north) from where the wind is blowing.</param>
<param index="4" label="Direction accuracy" units="deg">Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown.</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
<enum name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS" bitmask="true">
<description>These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.</description>
<entry value="1" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_POSITION"/>
<entry value="2" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_VELOCITY"/>
<entry value="4" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_ACCELERATION"/>
<entry value="8" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_ATTITUDE"/>
<entry value="16" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_RATES"/>
</enum>
<enum name="TARGET_OBS_FRAME">
<description>The frame of a target observation from an onboard sensor.</description>
<entry value="0" name="TARGET_OBS_FRAME_LOCAL_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.</description>
</entry>
<entry value="1" name="TARGET_OBS_FRAME_BODY_FRD">
<description>FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.</description>
</entry>
<entry value="2" name="TARGET_OBS_FRAME_LOCAL_OFFSET_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with an origin that travels with vehicle.</description>
</entry>
<entry value="3" name="TARGET_OBS_FRAME_OTHER">
<description>Other sensor frame for target observations neither in local NED nor in body FRD.</description>
</entry>
</enum>
<enum name="RADIO_RC_CHANNELS_FLAGS" bitmask="true">
<description>RADIO_RC_CHANNELS flags (bitmask).</description>
<entry value="1" name="RADIO_RC_CHANNELS_FLAGS_FAILSAFE">
<description>Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.</description>
</entry>
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_OUTDATED">
<description>Channel data may be out of date. This is set when the receiver is unable to validate incoming data from the transmitter and has therefore resent the last valid data it received.</description>
</entry>
</enum>
<enum name="MAV_FUEL_TYPE">
<description>Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates.</description>
<entry value="0" name="MAV_FUEL_TYPE_UNKNOWN">
<description>Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1.</description>
</entry>
<entry value="1" name="MAV_FUEL_TYPE_LIQUID">
<description>A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second.</description>
</entry>
<entry value="2" name="MAV_FUEL_TYPE_GAS">
<description>A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s).</description>
</entry>
</enum>
<enum name="GPS_SYSTEM_ERROR_FLAGS" bitmask="true">
<description>Flags indicating errors in a GPS receiver.</description>
<entry value="1" name="GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS">
<description>There are problems with incoming correction streams.</description>
</entry>
<entry value="2" name="GPS_SYSTEM_ERROR_CONFIGURATION">
<description>There are problems with the configuration.</description>
</entry>
<entry value="4" name="GPS_SYSTEM_ERROR_SOFTWARE">
<description>There are problems with the software on the GPS receiver.</description>
</entry>
<entry value="8" name="GPS_SYSTEM_ERROR_ANTENNA">
<description>There are problems with an antenna connected to the GPS receiver.</description>
</entry>
<entry value="16" name="GPS_SYSTEM_ERROR_EVENT_CONGESTION">
<description>There are problems handling all incoming events.</description>
</entry>
<entry value="32" name="GPS_SYSTEM_ERROR_CPU_OVERLOAD">
<description>The GPS receiver CPU is overloaded.</description>
</entry>
<entry value="64" name="GPS_SYSTEM_ERROR_OUTPUT_CONGESTION">
<description>The GPS receiver is experiencing output congestion.</description>
</entry>
</enum>
<enum name="GPS_AUTHENTICATION_STATE">
<description>Signal authentication state in a GPS receiver.</description>
<entry value="0" name="GPS_AUTHENTICATION_STATE_UNKNOWN">
<description>The GPS receiver does not provide GPS signal authentication info.</description>
</entry>
<entry value="1" name="GPS_AUTHENTICATION_STATE_INITIALIZING">
<description>The GPS receiver is initializing signal authentication.</description>
</entry>
<entry value="2" name="GPS_AUTHENTICATION_STATE_ERROR">
<description>The GPS receiver encountered an error while initializing signal authentication.</description>
</entry>
<entry value="3" name="GPS_AUTHENTICATION_STATE_OK">
<description>The GPS receiver has correctly authenticated all signals.</description>
</entry>
<entry value="4" name="GPS_AUTHENTICATION_STATE_DISABLED">
<description>GPS signal authentication is disabled on the receiver.</description>
</entry>
</enum>
<enum name="GPS_JAMMING_STATE">
<description>Signal jamming state in a GPS receiver.</description>
<entry value="0" name="GPS_JAMMING_STATE_UNKNOWN">
<description>The GPS receiver does not provide GPS signal jamming info.</description>
</entry>
<entry value="1" name="GPS_JAMMING_STATE_OK">
<description>The GPS receiver detected no signal jamming.</description>
</entry>
<entry value="2" name="GPS_JAMMING_STATE_MITIGATED">
<description>The GPS receiver detected and mitigated signal jamming.</description>
</entry>
<entry value="3" name="GPS_JAMMING_STATE_DETECTED">
<description>The GPS receiver detected signal jamming.</description>
</entry>
</enum>
<enum name="GPS_SPOOFING_STATE">
<description>Signal spoofing state in a GPS receiver.</description>
<entry value="0" name="GPS_SPOOFING_STATE_UNKNOWN">
<description>The GPS receiver does not provide GPS signal spoofing info.</description>
</entry>
<entry value="1" name="GPS_SPOOFING_STATE_OK">
<description>The GPS receiver detected no signal spoofing.</description>
</entry>
<entry value="2" name="GPS_SPOOFING_STATE_MITIGATED">
<description>The GPS receiver detected and mitigated signal spoofing.</description>
</entry>
<entry value="3" name="GPS_SPOOFING_STATE_DETECTED">
<description>The GPS receiver detected signal spoofing but still has a fix.</description>
</entry>
</enum>
<enum name="GPS_RAIM_STATE">
<description>State of RAIM processing.</description>
<entry value="0" name="GPS_RAIM_STATE_UNKNOWN">
<description>RAIM capability is unknown.</description>
</entry>
<entry value="1" name="GPS_RAIM_STATE_DISABLED">
<description>RAIM is disabled.</description>
</entry>
<entry value="2" name="GPS_RAIM_STATE_OK">
<description>RAIM integrity check was successful.</description>
</entry>
<entry value="3" name="GPS_RAIM_STATE_FAILED">
<description>RAIM integrity check failed.</description>
</entry>
</enum>
</enums>
<messages>
<!-- Transactions for parameter protocol -->
<message id="19" name="PARAM_ACK_TRANSACTION">
<description>Response from a PARAM_SET message when it is used in a transaction.</description>
<field type="uint8_t" name="target_system">Id of system that sent PARAM_SET message.</field>
<field type="uint8_t" name="target_component">Id of system that sent PARAM_SET message.</field>
<field type="char[16]" name="param_id">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</field>
<field type="float" name="param_value">Parameter value (new value if PARAM_ACCEPTED, current value otherwise)</field>
<field type="uint8_t" name="param_type" enum="MAV_PARAM_TYPE">Parameter type.</field>
<field type="uint8_t" name="param_result" enum="PARAM_ACK">Result code.</field>
</message>
<message id="295" name="AIRSPEED">
<description>Airspeed information from a sensor.</description>
<field type="uint8_t" name="id" instance="true">Sensor ID.</field>
<field type="float" name="airspeed" units="m/s">Calibrated airspeed (CAS).</field>
<field type="int16_t" name="temperature" units="cdegC">Temperature. INT16_MAX for value unknown/not supplied.</field>
<field type="float" name="raw_press" units="hPa">Raw differential pressure. NaN for value unknown/not supplied.</field>
<field type="uint8_t" name="flags" enum="AIRSPEED_SENSOR_FLAGS">Airspeed sensor flags.</field>
</message>
<message id="298" name="WIFI_NETWORK_INFO">
<description>Detected WiFi network status information. This message is sent per each WiFi network detected in range with known SSID and general status parameters.</description>
<field type="char[32]" name="ssid">Name of Wi-Fi network (SSID).</field>
<field type="uint8_t" name="channel_id">WiFi network operating channel ID. Set to 0 if unknown or unidentified.</field>
<field type="uint8_t" name="signal_quality" units="%">WiFi network signal quality.</field>
<field type="uint16_t" name="data_rate" units="MiB/s">WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.</field>
<field type="uint8_t" name="security" enum="WIFI_NETWORK_SECURITY">WiFi network security type.</field>
</message>
<message id="354" name="SET_VELOCITY_LIMITS">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Set temporary maximum limits for horizontal speed, vertical speed and yaw rate.
The consumer must stream the current limits in VELOCITY_LIMITS at 1 Hz or more (when limits are being set).
The consumer should latch the limits until a new limit is received or the mode is changed.
</description>
<field type="uint8_t" name="target_system">System ID (0 for broadcast).</field>
<field type="uint8_t" name="target_component">Component ID (0 for broadcast).</field>
<field type="float" name="horizontal_speed_limit" default="NaN" units="m/s">Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)</field>
<field type="float" name="vertical_speed_limit" default="NaN" units="m/s">Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)</field>
<field type="float" name="yaw_rate_limit" default="NaN" units="rad/s">Limit for vehicle turn rate around its yaw axis. NaN: Field not used (ignore)</field>
</message>
<message id="355" name="VELOCITY_LIMITS">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Current limits for horizontal speed, vertical speed and yaw rate, as set by SET_VELOCITY_LIMITS.</description>
<field type="float" name="horizontal_speed_limit" default="NaN" units="m/s">Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied</field>
<field type="float" name="vertical_speed_limit" default="NaN" units="m/s">Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied</field>
<field type="float" name="yaw_rate_limit" default="NaN" units="rad/s">Limit for vehicle turn rate around its yaw axis. NaN: No limit applied</field>
</message>
<message id="361" name="FIGURE_EIGHT_EXECUTION_STATUS">
<wip/>
<!-- This message is work-in-progress it can therefore change, and should NOT be used in stable production environments -->
<description>
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.
</description>
<field type="uint64_t" name="time_usec" units="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.</field>
<field type="float" name="major_radius" units="m">Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.</field>
<field type="float" name="minor_radius" units="m">Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.</field>
<field type="float" name="orientation" units="rad">Orientation of the figure eight major axis with respect to true north in [-pi,pi).</field>
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the fields: x, y, z.</field>
<field type="int32_t" name="x">X coordinate of center point. Coordinate system depends on frame field.</field>
<field type="int32_t" name="y">Y coordinate of center point. Coordinate system depends on frame field.</field>
<field type="float" name="z" units="m">Altitude of center point. Coordinate system depends on frame field.</field>
</message>
<message id="369" name="BATTERY_STATUS_V2">
<description>Battery dynamic information.
This should be streamed (nominally at 1Hz).
Static/invariant battery information is sent in 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.
</description>
<field type="uint8_t" name="id" instance="true">Battery ID</field>
<field type="int16_t" name="temperature" units="cdegC" invalid="INT16_MAX">Temperature of the whole battery pack (not internal electronics). INT16_MAX field not provided.</field>
<field type="float" name="voltage" units="V" invalid="NaN">Battery voltage (total). NaN: field not provided.</field>
<field type="float" name="current" units="A" invalid="NaN">Battery current (through all cells/loads). Positive value when discharging and negative if charging. NaN: field not provided.</field>
<field type="float" name="capacity_consumed" units="Ah" invalid="NaN">Consumed 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.</field>
<field type="float" name="capacity_remaining" units="Ah" invalid="NaN">Remaining charge (until empty). NaN: 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.</field>
<field type="uint8_t" name="percent_remaining" units="%" invalid="UINT8_MAX">Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided.</field>
<field type="uint32_t" name="status_flags" display="bitmask" enum="MAV_BATTERY_STATUS_FLAGS">Fault, health, readiness, and other status indications.</field>
</message>
<message id="371" name="FUEL_STATUS">
<description>Fuel status.
This message provides "generic" fuel level information for display in a GCS and for triggering failsafes in an autopilot.
The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE.
The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value.
A recipient can assume that if these fields are supplied they are accurate.
If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume).
Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot).
This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2.
If both messages are sent for the same fuel system, the ids and corresponding information must match.
This should be streamed (nominally at 0.1 Hz).
</description>
<field type="uint8_t" name="id" instance="true">Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2.</field>
<field type="float" name="maximum_fuel">Capacity when full. Must be provided.</field>
<field type="float" name="consumed_fuel" invalid="NaN">Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided.</field>
<field type="float" name="remaining_fuel" invalid="NaN">Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided.</field>
<field type="uint8_t" name="percent_remaining" units="%" invalid="UINT8_MAX">Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided.</field>
<field type="float" name="flow_rate" invalid="NaN">Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided.</field>
<field type="float" name="temperature" units="K" invalid="NaN">Fuel temperature. NaN: field not provided.</field>
<field type="uint32_t" name="fuel_type" enum="MAV_FUEL_TYPE">Fuel type. Defines units for fuel capacity and consumption fields above.</field>
</message>
<message id="414" name="GROUP_START">
<description>Emitted during mission execution when control reaches MAV_CMD_GROUP_START.</description>
<field type="uint32_t" name="group_id">Mission-unique group id (from MAV_CMD_GROUP_START).</field>
<field type="uint32_t" name="mission_checksum">CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.</field>
<field type="uint64_t" name="time_usec" units="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.</field>
</message>
<message id="415" name="GROUP_END">
<description>Emitted during mission execution when control reaches MAV_CMD_GROUP_END.</description>
<field type="uint32_t" name="group_id">Mission-unique group id (from MAV_CMD_GROUP_END).</field>
<field type="uint32_t" name="mission_checksum">CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.</field>
<field type="uint64_t" name="time_usec" units="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.</field>
</message>
<message id="420" name="RADIO_RC_CHANNELS">
<description>RC channel outputs from a MAVLink RC receiver for input to a flight controller or other components (allows an RC receiver to connect via MAVLink instead of some other protocol such as PPM-Sum or S.BUS).
Note that this is not intended to be an over-the-air format, and does not replace RC_CHANNELS and similar messages reported by the flight controller.
The target_system field should normally be set to the system id of the system to control, typically the flight controller.
The target_component field can normally be set to 0, so that all components of the system can receive the message.
The channels array field can publish up to 32 channels; the number of channel items used in the array is specified in the count field.
The time_last_update_ms field contains the timestamp of the last received valid channels data in the receiver's time domain.
The count field indicates the first index of the channel array that is not used for channel data (this and later indexes are zero-filled).
The RADIO_RC_CHANNELS_FLAGS_OUTDATED flag is set by the receiver if the channels data is not up-to-date (for example, if new data from the transmitter could not be validated so the last valid data is resent).
The RADIO_RC_CHANNELS_FLAGS_FAILSAFE failsafe flag is set by the receiver if the receiver's failsafe condition is met (implementation dependent, e.g., connection to the RC radio is lost).
In this case time_last_update_ms still contains the timestamp of the last valid channels data, but the content of the channels data is not defined by the protocol (it is up to the implementation of the receiver).
For instance, the channels data could contain failsafe values configured in the receiver; the default is to carry the last valid data.
Note: The RC channels fields are extensions to ensure that they are located at the end of the serialized payload and subject to MAVLink's trailing-zero trimming.
</description>
<field type="uint8_t" name="target_system">System ID (ID of target system, normally flight controller).</field>
<field type="uint8_t" name="target_component">Component ID (normally 0 for broadcast).</field>
<field type="uint32_t" name="time_last_update_ms" units="ms">Time when the data in the channels field were last updated (time since boot in the receiver's time domain).</field>
<field type="uint16_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio RC channels status flags.</field>
<field type="uint8_t" name="count">Total number of RC channels being received. This can be larger than 32, indicating that more channels are available but not given in this message.</field>
<extensions/>
<field type="int16_t[32]" name="channels" minValue="-4096" maxValue="4096">RC channels.
Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming.</field>
</message>
<message id="435" name="AVAILABLE_MODES">
<description>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).
</description>
<field type="uint8_t" name="number_modes">The total number of available modes for the current vehicle type.</field>
<field type="uint8_t" name="mode_index">The current mode index within number_modes, indexed from 1.</field>
<field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field>
<field type="uint32_t" name="properties" enum="MAV_MODE_PROPERTY">Mode properties.</field>
<field type="char[35]" name="mode_name">Name of custom mode, with null termination character. Should be omitted for standard modes.</field>
</message>
<message id="436" name="CURRENT_MODE">
<description>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.
</description>
<field type="uint8_t" name="standard_mode" enum="MAV_STANDARD_MODE">Standard mode.</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field>
<field type="uint32_t" name="intended_custom_mode" invalid="0">The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied</field>
</message>
<message id="437" name="AVAILABLE_MODES_MONITOR">
<description>A change to the sequence number indicates that the set of AVAILABLE_MODES has changed.
A receiver must re-request all available modes whenever the sequence number changes.
This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change.
</description>
<field type="uint8_t" name="seq">Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically).</field>
</message>
<message id="441" name="GNSS_INTEGRITY">
<description>Information about key components of GNSS receivers, like signal authentication, interference and system errors.</description>
<field type="uint8_t" name="id" instance="true">GNSS receiver id. Must match instance ids of other messages from same receiver.</field>
<field type="uint32_t" name="system_errors" enum="GPS_SYSTEM_ERROR_FLAGS" display="bitmask">Errors in the GPS system.</field>
<field type="uint8_t" name="authentication_state" enum="GPS_AUTHENTICATION_STATE">Signal authentication state of the GPS system.</field>
<field type="uint8_t" name="jamming_state" enum="GPS_JAMMING_STATE">Signal jamming state of the GPS system.</field>
<field type="uint8_t" name="spoofing_state" enum="GPS_SPOOFING_STATE">Signal spoofing state of the GPS system.</field>
<field type="uint8_t" name="raim_state" enum="GPS_RAIM_STATE">The state of the RAIM processing.</field>
<field type="uint16_t" name="raim_hfom" units="cm" invalid="UINT16_MAX">Horizontal expected accuracy using satellites successfully validated using RAIM.</field>
<field type="uint16_t" name="raim_vfom" units="cm" invalid="UINT16_MAX">Vertical expected accuracy using satellites successfully validated using RAIM.</field>
<field type="uint8_t" name="corrections_quality" minValue="0" maxValue="10" invalid="UINT8_MAX">An abstract value representing the estimated quality of incoming corrections, or 255 if not available.</field>
<field type="uint8_t" name="system_status_summary" minValue="0" maxValue="10" invalid="UINT8_MAX">An abstract value representing the overall status of the receiver, or 255 if not available.</field>
<field type="uint8_t" name="gnss_signal_quality" minValue="0" maxValue="10" invalid="UINT8_MAX">An abstract value representing the quality of incoming GNSS signals, or 255 if not available.</field>
<field type="uint8_t" name="post_processing_quality" minValue="0" maxValue="10" invalid="UINT8_MAX">An abstract value representing the estimated PPK quality, or 255 if not available.</field>
</message>
<!-- Target info from a sensor on the target -->
<message id="510" name="TARGET_ABSOLUTE">
<description>Current motion information from sensors on a target</description>
<field type="uint64_t" name="timestamp" units="us">Timestamp (UNIX epoch time).</field>
<field type="uint8_t" name="id">The ID of the target if multiple targets are present</field>
<field type="uint8_t" name="sensor_capabilities" enum="TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS" display="bitmask">Bitmap to indicate the sensor's reporting capabilities</field>
<field type="int32_t" name="lat" units="degE7">Target's latitude (WGS84)</field>
<field type="int32_t" name="lon" units="degE7">Target's longitude (WGS84)</field>
<field type="float" name="alt" units="m">Target's altitude (AMSL)</field>
<field type="float[3]" name="vel" units="m/s" invalid="[0]">Target's velocity in its body frame</field>
<field type="float[3]" name="acc" units="m/s/s" invalid="[0]">Linear target's acceleration in its body frame</field>
<field type="float[4]" name="q_target" invalid="[0]">Quaternion of the target's orientation from its body frame to the vehicle's NED frame.</field>
<field type="float[3]" name="rates" units="rad/s" invalid="[0]">Target's roll, pitch and yaw rates</field>
<field type="float[2]" name="position_std" units="m">Standard deviation of horizontal (eph) and vertical (epv) position errors</field>
<field type="float[3]" name="vel_std" units="m/s">Standard deviation of the target's velocity in its body frame</field>
<field type="float[3]" name="acc_std" units="m/s/s">Standard deviation of the target's acceleration in its body frame</field>
</message>
<!-- Target info measured by MAV's onboard sensors -->
<message id="511" name="TARGET_RELATIVE">
<description>The location of a target measured by MAV's onboard sensors. </description>
<field type="uint64_t" name="timestamp" units="us">Timestamp (UNIX epoch time)</field>
<field type="uint8_t" name="id" instance="true">The ID of the target if multiple targets are present</field>
<field type="uint8_t" name="frame" enum="TARGET_OBS_FRAME">Coordinate frame used for following fields.</field>
<field type="float" name="x" units="m">X Position of the target in TARGET_OBS_FRAME</field>
<field type="float" name="y" units="m">Y Position of the target in TARGET_OBS_FRAME</field>
<field type="float" name="z" units="m">Z Position of the target in TARGET_OBS_FRAME</field>
<field type="float[3]" name="pos_std" units="m">Standard deviation of the target's position in TARGET_OBS_FRAME</field>
<field type="float" name="yaw_std" units="rad">Standard deviation of the target's orientation in TARGET_OBS_FRAME</field>
<field type="float[4]" name="q_target">Quaternion of the target's orientation from the target's frame to the TARGET_OBS_FRAME (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
<field type="float[4]" name="q_sensor">Quaternion of the sensor's orientation from TARGET_OBS_FRAME to vehicle-carried NED. (Ignored if set to (0,0,0,0)) (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
<field type="uint8_t" name="type" enum="LANDING_TARGET_TYPE">Type of target</field>
</message>
</messages>
</mavlink>