common.xml
0
0
WiFi wireless security protocols.
Undefined or unknown security protocol.
Open network, no security.
WEP.
WPA1.
WPA2.
WPA3.
Airspeed sensor flags
Airspeed sensor is unhealthy
True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.
Possible transport layers to set and get parameters via mavlink during a parameter transaction.
Transaction over param transport.
Transaction over param_ext transport.
Possible parameter transaction actions.
Commit the current parameter transaction.
Commit the current parameter transaction.
Cancel the current parameter transaction.
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.
Non standard mode.
This may be used when reporting the mode if the current flight mode is not a standard mode.
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).
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).
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).
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).
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.
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.
Mission mode (automatic).
Automatic mode that executes MAVLink missions.
Missions are executed from the current waypoint as soon as the mode is enabled.
Land mode (auto).
Automatic mode that lands the vehicle at the current location.
The precise landing behaviour depends on vehicle configuration and type.
Takeoff mode (auto).
Automatic takeoff mode.
The precise takeoff behaviour depends on vehicle configuration and type.
Mode properties.
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.
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).
Battery status flags for fault, health and state indication.
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).
Battery is charging.
Battery is cell balancing (during charging).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE may be set).
Battery cells are not balanced.
Not ready to use.
Battery is auto discharging (towards storage level).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE would be set).
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.).
Battery is faulty and cannot be repaired (not safe to fly).
This is set at vendor discretion.
The battery should be disposed of safely.
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.
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.
One or more cells are above their maximum voltage rating.
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.
Over-temperature fault.
Under-temperature fault.
Over-current fault.
Short circuit event detected.
The battery may or may not be safe to use (check other flags).
Voltage not compatible with power rail voltage (batteries on same power rail should have similar voltage).
Battery firmware is not compatible with current autopilot firmware.
Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).
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.
Reserved (not used). If set, this will indicate that an additional status field exists for higher status values.
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
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).
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.
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.
Orientation of the figure eight major axis with respect to true north (range: [-pi,pi]). NaN: use default orientation aligned to true north.
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.
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.
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.
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.
Action to be performed (start, commit, cancel, etc.)
Possible transport layers to set and get parameters via mavlink during a parameter transaction.
Identifier for a specific transaction.
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.
Component id of the component to be upgraded. If set to 0, all components should be upgraded.
0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed.
Reserved
Reserved
Reserved
Reserved
WIP: upgrade progress report rate (can be used for more granular control).
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.
Mission-unique group id.
Group id is limited because only 24 bit integer can be stored in 32 bit float.
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.
Mission-unique group id.
Group id is limited because only 24 bit integer can be stored in 32 bit float.
Enable the specified standard MAVLink mode.
If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED.
The mode to set.
Allows setting an AT S command of an SiK radio.
The radio instance, one-based, 0 for all.
The Sx index, e.g. 3 for S3 which is NETID.
The value to set it to, e.g. default 25 for NETID
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.
New system ID for target component(s). 0: ignore and reject command (broadcast system ID not allowed).
New component ID for target component(s). 0: ignore (component IDs don't change).
Reboot components after ID change. Any non-zero value triggers the reboot.
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.
Set/unset emergency 0: unset, 1: set
Empty
Empty
Empty
Empty
Empty
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.
Horizontal wind speed.
Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown.
Azimuth (relative to true north) from where the wind is blowing.
Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown.
Empty
Empty
Empty
These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.
The frame of a target observation from an onboard sensor.
NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
NED local tangent frame (x: North, y: East, z: Down) with an origin that travels with vehicle.
Other sensor frame for target observations neither in local NED nor in body FRD.
RADIO_RC_CHANNELS flags (bitmask).
Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.
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.
Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates.
Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1.
A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second.
A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s).
Flags indicating errors in a GPS receiver.
There are problems with incoming correction streams.
There are problems with the configuration.
There are problems with the software on the GPS receiver.
There are problems with an antenna connected to the GPS receiver.
There are problems handling all incoming events.
The GPS receiver CPU is overloaded.
The GPS receiver is experiencing output congestion.
Signal authentication state in a GPS receiver.
The GPS receiver does not provide GPS signal authentication info.
The GPS receiver is initializing signal authentication.
The GPS receiver encountered an error while initializing signal authentication.
The GPS receiver has correctly authenticated all signals.
GPS signal authentication is disabled on the receiver.
Signal jamming state in a GPS receiver.
The GPS receiver does not provide GPS signal jamming info.
The GPS receiver detected no signal jamming.
The GPS receiver detected and mitigated signal jamming.
The GPS receiver detected signal jamming.
Signal spoofing state in a GPS receiver.
The GPS receiver does not provide GPS signal spoofing info.
The GPS receiver detected no signal spoofing.
The GPS receiver detected and mitigated signal spoofing.
The GPS receiver detected signal spoofing but still has a fix.
State of RAIM processing.
RAIM capability is unknown.
RAIM is disabled.
RAIM integrity check was successful.
RAIM integrity check failed.
Response from a PARAM_SET message when it is used in a transaction.
Id of system that sent PARAM_SET message.
Id of system that sent PARAM_SET message.
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
Parameter value (new value if PARAM_ACCEPTED, current value otherwise)
Parameter type.
Result code.
Airspeed information from a sensor.
Sensor ID.
Calibrated airspeed (CAS).
Temperature. INT16_MAX for value unknown/not supplied.
Raw differential pressure. NaN for value unknown/not supplied.
Airspeed sensor flags.
Detected WiFi network status information. This message is sent per each WiFi network detected in range with known SSID and general status parameters.
Name of Wi-Fi network (SSID).
WiFi network operating channel ID. Set to 0 if unknown or unidentified.
WiFi network signal quality.
WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
WiFi network security type.
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.
System ID (0 for broadcast).
Component ID (0 for broadcast).
Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)
Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)
Limit for vehicle turn rate around its yaw axis. NaN: Field not used (ignore)
Current limits for horizontal speed, vertical speed and yaw rate, as set by SET_VELOCITY_LIMITS.
Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied
Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied
Limit for vehicle turn rate around its yaw axis. NaN: No limit applied
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.
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.
Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
Orientation of the figure eight major axis with respect to true north in [-pi,pi).
The coordinate system of the fields: x, y, z.
X coordinate of center point. Coordinate system depends on frame field.
Y coordinate of center point. Coordinate system depends on frame field.
Altitude of center point. Coordinate system depends on frame field.
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.
Battery ID
Temperature of the whole battery pack (not internal electronics). INT16_MAX field not provided.
Battery voltage (total). NaN: field not provided.
Battery current (through all cells/loads). Positive value when discharging and negative if charging. NaN: field not provided.
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.
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.
Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided.
Fault, health, readiness, and other status indications.
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).
Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2.
Capacity when full. Must be provided.
Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided.
Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided.
Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided.
Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided.
Fuel temperature. NaN: field not provided.
Fuel type. Defines units for fuel capacity and consumption fields above.
Emitted during mission execution when control reaches MAV_CMD_GROUP_START.
Mission-unique group id (from MAV_CMD_GROUP_START).
CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
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.
Emitted during mission execution when control reaches MAV_CMD_GROUP_END.
Mission-unique group id (from MAV_CMD_GROUP_END).
CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
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.
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.
System ID (ID of target system, normally flight controller).
Component ID (normally 0 for broadcast).
Time when the data in the channels field were last updated (time since boot in the receiver's time domain).
Radio RC channels status flags.
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.
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.
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).
The total number of available modes for the current vehicle type.
The current mode index within number_modes, indexed from 1.
Standard mode.
A bitfield for use for autopilot-specific flags
Mode properties.
Name of custom mode, with null termination character. Should be omitted for standard modes.
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.
Standard mode.
A bitfield for use for autopilot-specific flags
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
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.
Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically).
Information about key components of GNSS receivers, like signal authentication, interference and system errors.
GNSS receiver id. Must match instance ids of other messages from same receiver.
Errors in the GPS system.
Signal authentication state of the GPS system.
Signal jamming state of the GPS system.
Signal spoofing state of the GPS system.
The state of the RAIM processing.
Horizontal expected accuracy using satellites successfully validated using RAIM.
Vertical expected accuracy using satellites successfully validated using RAIM.
An abstract value representing the estimated quality of incoming corrections, or 255 if not available.
An abstract value representing the overall status of the receiver, or 255 if not available.
An abstract value representing the quality of incoming GNSS signals, or 255 if not available.
An abstract value representing the estimated PPK quality, or 255 if not available.
Current motion information from sensors on a target
Timestamp (UNIX epoch time).
The ID of the target if multiple targets are present
Bitmap to indicate the sensor's reporting capabilities
Target's latitude (WGS84)
Target's longitude (WGS84)
Target's altitude (AMSL)
Target's velocity in its body frame
Linear target's acceleration in its body frame
Quaternion of the target's orientation from its body frame to the vehicle's NED frame.
Target's roll, pitch and yaw rates
Standard deviation of horizontal (eph) and vertical (epv) position errors
Standard deviation of the target's velocity in its body frame
Standard deviation of the target's acceleration in its body frame
The location of a target measured by MAV's onboard sensors.
Timestamp (UNIX epoch time)
The ID of the target if multiple targets are present
Coordinate frame used for following fields.
X Position of the target in TARGET_OBS_FRAME
Y Position of the target in TARGET_OBS_FRAME
Z Position of the target in TARGET_OBS_FRAME
Standard deviation of the target's position in TARGET_OBS_FRAME
Standard deviation of the target's orientation in TARGET_OBS_FRAME
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)
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)
Type of target