Skip to content

Latest commit

 

History

History
693 lines (489 loc) · 55.4 KB

development.md

File metadata and controls

693 lines (489 loc) · 55.4 KB

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.

::: info

  • MAVLink 2 extension fields are displayed in blue.
  • Entities from dialects are displayed only as headings (with link to original)

:::

<style> span.ext { color: blue; } span.warning { color: red; } </style>

Protocol dialect: 0

Protocol version: 0

MAVLink Include Files

Summary

Type Defined Included
Messages 15 226
Enums 13 144
Commands 172 0

The following sections list all entities in the dialect (both included and defined in this file).

Messages

AIRSPEED (295) — [WIP] {#AIRSPEED}

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

Airspeed information from a sensor.

Field Name Type Units Values Description
id uint8_t Sensor ID.
Messages with same value are from the same source (instance).
airspeed float m/s Calibrated airspeed (CAS).
temperature int16_t cdegC Temperature. INT16_MAX for value unknown/not supplied.
raw_press float hPa Raw differential pressure. NaN for value unknown/not supplied.
flags uint8_t AIRSPEED_SENSOR_FLAGS Airspeed sensor flags.

SET_VELOCITY_LIMITS (354) — [WIP] {#SET_VELOCITY_LIMITS}

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

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.

Field Name Type Units Description
target_system uint8_t System ID (0 for broadcast).
target_component uint8_t Component ID (0 for broadcast).
horizontal_speed_limit float m/s Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)
vertical_speed_limit float m/s Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: Field not used (ignore)
yaw_rate_limit float rad/s Limit for vehicle turn rate around its yaw axis. NaN: Field not used (ignore)

VELOCITY_LIMITS (355) — [WIP] {#VELOCITY_LIMITS}

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

Current limits for horizontal speed, vertical speed and yaw rate, as set by SET_VELOCITY_LIMITS.

Field Name Type Units Description
horizontal_speed_limit float m/s Limit for horizontal movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied
vertical_speed_limit float m/s Limit for vertical movement in MAV_FRAME_LOCAL_NED. NaN: No limit applied
yaw_rate_limit float rad/s Limit for vehicle turn rate around its yaw axis. NaN: No limit applied

FIGURE_EIGHT_EXECUTION_STATUS (361) — [WIP] {#FIGURE_EIGHT_EXECUTION_STATUS}

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

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 Name Type Units Values Description
time_usec uint64_t us Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
major_radius float m Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
minor_radius float m Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
orientation float rad Orientation of the figure eight major axis with respect to true north in [-pi,pi).
frame uint8_t MAV_FRAME The coordinate system of the fields: x, y, z.
x int32_t X coordinate of center point. Coordinate system depends on frame field.
y int32_t Y coordinate of center point. Coordinate system depends on frame field.
z float m Altitude of center point. Coordinate system depends on frame field.

BATTERY_STATUS_V2 (369) — [WIP] {#BATTERY_STATUS_V2}

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

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.

Field Name Type Units Values Description
id uint8_t Battery ID
Messages with same value are from the same source (instance).
temperature int16_t cdegC invalid:INT16_MAX Temperature of the whole battery pack (not internal electronics). INT16_MAX field not provided.
voltage float V invalid:NaN Battery voltage (total). NaN: field not provided.
current float A invalid:NaN Battery current (through all cells/loads). Positive value when discharging and negative if charging. NaN: field not provided.
capacity_consumed float 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.
capacity_remaining float 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.
percent_remaining uint8_t % invalid:UINT8_MAX Remaining battery energy. Values: [0-100], UINT8_MAX: field not provided.
status_flags uint32_t MAV_BATTERY_STATUS_FLAGS Fault, health, readiness, and other status indications.

GROUP_START (414) — [WIP] {#GROUP_START}

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

Emitted during mission execution when control reaches MAV_CMD_GROUP_START.

Field Name Type Units Description
group_id uint32_t Mission-unique group id (from MAV_CMD_GROUP_START).
mission_checksum uint32_t CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
time_usec uint64_t us Timestamp (UNIX Epoch time or time since system boot).
The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.

GROUP_END (415) — [WIP] {#GROUP_END}

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

Emitted during mission execution when control reaches MAV_CMD_GROUP_END.

Field Name Type Units Description
group_id uint32_t Mission-unique group id (from MAV_CMD_GROUP_END).
mission_checksum uint32_t CRC32 checksum of current plan for MAV_MISSION_TYPE_ALL. As defined in MISSION_CHECKSUM message.
time_usec uint64_t us Timestamp (UNIX Epoch time or time since system boot).
The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.

RADIO_RC_CHANNELS (420) — [WIP] {#RADIO_RC_CHANNELS}

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

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.

Field Name Type Units Values Description
target_system uint8_t System ID (ID of target system, normally flight controller).
target_component uint8_t Component ID (normally 0 for broadcast).
time_last_update_ms uint32_t ms Time when the data in the channels field were last updated (time since boot in the receiver's time domain).
flags uint16_t RADIO_RC_CHANNELS_FLAGS Radio RC channels status flags.
count uint8_t 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.
channels ++ int16_t[32] min:-4096 max: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.

AVAILABLE_MODES (435) — [WIP] {#AVAILABLE_MODES}

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

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 Name Type Values Description
number_modes uint8_t The total number of available modes for the current vehicle type.
mode_index uint8_t The current mode index within number_modes, indexed from 1.
standard_mode uint8_t MAV_STANDARD_MODE Standard mode.
custom_mode uint32_t A bitfield for use for autopilot-specific flags
properties uint32_t MAV_MODE_PROPERTY Mode properties.
mode_name char[35] Name of custom mode, with null termination character. Should be omitted for standard modes.

CURRENT_MODE (436) — [WIP] {#CURRENT_MODE}

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

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 Name Type Values Description
standard_mode uint8_t MAV_STANDARD_MODE Standard mode.
custom_mode uint32_t A bitfield for use for autopilot-specific flags
intended_custom_mode uint32_t 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

AVAILABLE_MODES_MONITOR (437) — [WIP] {#AVAILABLE_MODES_MONITOR}

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

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.

Field Name Type Description
seq uint8_t Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically).

GNSS_INTEGRITY (441) — [WIP] {#GNSS_INTEGRITY}

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

Information about key components of GNSS receivers, like signal authentication, interference and system errors.

Field Name Type Units Values Description
id uint8_t GNSS receiver id. Must match instance ids of other messages from same receiver.
Messages with same value are from the same source (instance).
system_errors uint32_t GPS_SYSTEM_ERROR_FLAGS Errors in the GPS system.
authentication_state uint8_t GPS_AUTHENTICATION_STATE Signal authentication state of the GPS system.
jamming_state uint8_t GPS_JAMMING_STATE Signal jamming state of the GPS system.
spoofing_state uint8_t GPS_SPOOFING_STATE Signal spoofing state of the GPS system.
raim_state uint8_t GPS_RAIM_STATE The state of the RAIM processing.
raim_hfom uint16_t cm invalid:UINT16_MAX Horizontal expected accuracy using satellites successfully validated using RAIM.
raim_vfom uint16_t cm invalid:UINT16_MAX Vertical expected accuracy using satellites successfully validated using RAIM.
corrections_quality uint8_t invalid:UINT8_MAX min:0 max:10 An abstract value representing the estimated quality of incoming corrections, or 255 if not available.
system_status_summary uint8_t invalid:UINT8_MAX min:0 max:10 An abstract value representing the overall status of the receiver, or 255 if not available.
gnss_signal_quality uint8_t invalid:UINT8_MAX min:0 max:10 An abstract value representing the quality of incoming GNSS signals, or 255 if not available.
post_processing_quality uint8_t invalid:UINT8_MAX min:0 max:10 An abstract value representing the estimated PPK quality, or 255 if not available.

TARGET_ABSOLUTE (510) — [WIP] {#TARGET_ABSOLUTE}

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

Current motion information from sensors on a target

Field Name Type Units Values Description
timestamp uint64_t us Timestamp (UNIX epoch time).
id uint8_t The ID of the target if multiple targets are present
sensor_capabilities uint8_t TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS Bitmap to indicate the sensor's reporting capabilities
lat int32_t degE7 Target's latitude (WGS84)
lon int32_t degE7 Target's longitude (WGS84)
alt float m Target's altitude (AMSL)
vel float[3] m/s invalid:[0] Target's velocity in its body frame
acc float[3] m/s/s invalid:[0] Linear target's acceleration in its body frame
q_target float[4] invalid:[0] Quaternion of the target's orientation from its body frame to the vehicle's NED frame.
rates float[3] rad/s invalid:[0] Target's roll, pitch and yaw rates
position_std float[2] m Standard deviation of horizontal (eph) and vertical (epv) position errors
vel_std float[3] m/s Standard deviation of the target's velocity in its body frame
acc_std float[3] m/s/s Standard deviation of the target's acceleration in its body frame

TARGET_RELATIVE (511) — [WIP] {#TARGET_RELATIVE}

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

The location of a target measured by MAV's onboard sensors.

Field Name Type Units Values Description
timestamp uint64_t us Timestamp (UNIX epoch time)
id uint8_t The ID of the target if multiple targets are present
Messages with same value are from the same source (instance).
frame uint8_t TARGET_OBS_FRAME Coordinate frame used for following fields.
x float m X Position of the target in TARGET_OBS_FRAME
y float m Y Position of the target in TARGET_OBS_FRAME
z float m Z Position of the target in TARGET_OBS_FRAME
pos_std float[3] m Standard deviation of the target's position in TARGET_OBS_FRAME
yaw_std float rad Standard deviation of the target's orientation in TARGET_OBS_FRAME
q_target float[4] 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)
q_sensor float[4] 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 uint8_t LANDING_TARGET_TYPE Type of target

CONTROL_STATUS (512) — [WIP] {#CONTROL_STATUS}

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

Information about GCS in control of this MAV. This should be broadcast at low rate (nominally 1 Hz) and emitted when ownership or takeover status change. Control over MAV is requested using MAV_CMD_REQUEST_OPERATOR_CONTROL.

Field Name Type Values Description
sysid_in_control uint8_t System ID of GCS MAVLink component in control (0: no GCS in control).
flags uint8_t GCS_CONTROL_STATUS_FLAGS Control status. For example, whether takeover is allowed, and whether this message instance defines the default controlling GCS for the whole system.

Enumerated Types

AIRSPEED_SENSOR_FLAGS — [WIP] {#AIRSPEED_SENSOR_FLAGS}

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

(Bitmask) Airspeed sensor flags

Value Name Description
0 AIRSPEED_SENSOR_UNHEALTHY Airspeed sensor is unhealthy
1 AIRSPEED_SENSOR_USING True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control.

MAV_STANDARD_MODE — [WIP] {#MAV_STANDARD_MODE}

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

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.

Value Name Description
0 MAV_STANDARD_MODE_NON_STANDARD Non standard mode.
This may be used when reporting the mode if the current flight mode is not a standard mode.
1 MAV_STANDARD_MODE_POSITION_HOLD 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).
2 MAV_STANDARD_MODE_ORBIT 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 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).
3 MAV_STANDARD_MODE_CRUISE 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).
4 MAV_STANDARD_MODE_ALTITUDE_HOLD 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).
5 MAV_STANDARD_MODE_SAFE_RECOVERY Safe recovery mode (auto).
Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle.
This mode is more commonly referred to as RTL and/or or Smart RTL.
The precise return location, flight path, and landing behaviour depend on vehicle configuration and type.
For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent.
6 MAV_STANDARD_MODE_MISSION Mission mode (automatic).
Automatic mode that executes MAVLink missions.
Missions are executed from the current waypoint as soon as the mode is enabled.
7 MAV_STANDARD_MODE_LAND Land mode (auto).
Automatic mode that lands the vehicle at the current location.
The precise landing behaviour depends on vehicle configuration and type.
8 MAV_STANDARD_MODE_TAKEOFF Takeoff mode (auto).
Automatic takeoff mode.
The precise takeoff behaviour depends on vehicle configuration and type.

MAV_MODE_PROPERTY — [WIP] {#MAV_MODE_PROPERTY}

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

(Bitmask) Mode properties.

Value Name Description
1 MAV_MODE_PROPERTY_ADVANCED 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.
2 MAV_MODE_PROPERTY_NOT_USER_SELECTABLE 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).

MAV_BATTERY_STATUS_FLAGS — [WIP] {#MAV_BATTERY_STATUS_FLAGS}

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

(Bitmask) Battery status flags for fault, health and state indication.

Value Name Description
1 MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE 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).
2 MAV_BATTERY_STATUS_FLAGS_CHARGING Battery is charging.
4 MAV_BATTERY_STATUS_FLAGS_CELL_BALANCING Battery is cell balancing (during charging).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE may be set).
8 MAV_BATTERY_STATUS_FLAGS_FAULT_CELL_IMBALANCE Battery cells are not balanced.
Not ready to use.
16 MAV_BATTERY_STATUS_FLAGS_AUTO_DISCHARGING Battery is auto discharging (towards storage level).
Not ready to use (MAV_BATTERY_STATUS_FLAGS_NOT_READY_TO_USE would be set).
32 MAV_BATTERY_STATUS_FLAGS_REQUIRES_SERVICE 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.).
64 MAV_BATTERY_STATUS_FLAGS_BAD_BATTERY Battery is faulty and cannot be repaired (not safe to fly).
This is set at vendor discretion.
The battery should be disposed of safely.
128 MAV_BATTERY_STATUS_FLAGS_PROTECTIONS_ENABLED 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.
256 MAV_BATTERY_STATUS_FLAGS_FAULT_PROTECTION_SYSTEM 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.
512 MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_VOLT One or more cells are above their maximum voltage rating.
1024 MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_VOLT 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.
2048 MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_TEMPERATURE Over-temperature fault.
4096 MAV_BATTERY_STATUS_FLAGS_FAULT_UNDER_TEMPERATURE Under-temperature fault.
8192 MAV_BATTERY_STATUS_FLAGS_FAULT_OVER_CURRENT Over-current fault.
16384 MAV_BATTERY_STATUS_FLAGS_FAULT_SHORT_CIRCUIT Short circuit event detected.
The battery may or may not be safe to use (check other flags).
32768 MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_VOLTAGE Voltage not compatible with power rail voltage (batteries on same power rail should have similar voltage).
65536 MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_FIRMWARE Battery firmware is not compatible with current autopilot firmware.
131072 MAV_BATTERY_STATUS_FLAGS_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).
262144 MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL 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.
4294967295 MAV_BATTERY_STATUS_FLAGS_EXTENDED Reserved (not used). If set, this will indicate that an additional status field exists for higher status values.

GCS_CONTROL_STATUS_FLAGS — [WIP] {#GCS_CONTROL_STATUS_FLAGS}

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

(Bitmask) CONTROL_STATUS flags.

Value Name Description
1 GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER If set, this CONTROL_STATUS publishes the controlling GCS for the whole system. If unset, the CONTROL_STATUS indicates the controlling GCS for just the component emitting the message. Note that to request control of the system a GCS should send MAV_CMD_REQUEST_OPERATOR_CONTROL to the component emitting CONTROL_STATUS with this flag set.
2 GCS_CONTROL_STATUS_FLAGS_TAKEOVER_ALLOWED Takeover allowed (requests for control will be granted). If not set requests for control will be rejected, but the controlling GCS will be notified (and may release control or allow takeover).

TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS — [WIP] {#TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS}

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

(Bitmask) These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.

Value Name Description
1 TARGET_ABSOLUTE_SENSOR_CAPABILITY_POSITION
2 TARGET_ABSOLUTE_SENSOR_CAPABILITY_VELOCITY
4 TARGET_ABSOLUTE_SENSOR_CAPABILITY_ACCELERATION
8 TARGET_ABSOLUTE_SENSOR_CAPABILITY_ATTITUDE
16 TARGET_ABSOLUTE_SENSOR_CAPABILITY_RATES

TARGET_OBS_FRAME — [WIP] {#TARGET_OBS_FRAME}

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

The frame of a target observation from an onboard sensor.

Value Name Description
0 TARGET_OBS_FRAME_LOCAL_NED NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
1 TARGET_OBS_FRAME_BODY_FRD FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
2 TARGET_OBS_FRAME_LOCAL_OFFSET_NED NED local tangent frame (x: North, y: East, z: Down) with an origin that travels with vehicle.
3 TARGET_OBS_FRAME_OTHER Other sensor frame for target observations neither in local NED nor in body FRD.

RADIO_RC_CHANNELS_FLAGS — [WIP] {#RADIO_RC_CHANNELS_FLAGS}

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

(Bitmask) RADIO_RC_CHANNELS flags (bitmask).

Value Name Description
1 RADIO_RC_CHANNELS_FLAGS_FAILSAFE Failsafe is active. The content of the RC channels data in the RADIO_RC_CHANNELS message is implementation dependent.
2 RADIO_RC_CHANNELS_FLAGS_OUTDATED 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.

GPS_SYSTEM_ERROR_FLAGS — [WIP] {#GPS_SYSTEM_ERROR_FLAGS}

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

(Bitmask) Flags indicating errors in a GPS receiver.

Value Name Description
1 GPS_SYSTEM_ERROR_INCOMING_CORRECTIONS There are problems with incoming correction streams.
2 GPS_SYSTEM_ERROR_CONFIGURATION There are problems with the configuration.
4 GPS_SYSTEM_ERROR_SOFTWARE There are problems with the software on the GPS receiver.
8 GPS_SYSTEM_ERROR_ANTENNA There are problems with an antenna connected to the GPS receiver.
16 GPS_SYSTEM_ERROR_EVENT_CONGESTION There are problems handling all incoming events.
32 GPS_SYSTEM_ERROR_CPU_OVERLOAD The GPS receiver CPU is overloaded.
64 GPS_SYSTEM_ERROR_OUTPUT_CONGESTION The GPS receiver is experiencing output congestion.

GPS_AUTHENTICATION_STATE — [WIP] {#GPS_AUTHENTICATION_STATE}

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

Signal authentication state in a GPS receiver.

Value Name Description
0 GPS_AUTHENTICATION_STATE_UNKNOWN The GPS receiver does not provide GPS signal authentication info.
1 GPS_AUTHENTICATION_STATE_INITIALIZING The GPS receiver is initializing signal authentication.
2 GPS_AUTHENTICATION_STATE_ERROR The GPS receiver encountered an error while initializing signal authentication.
3 GPS_AUTHENTICATION_STATE_OK The GPS receiver has correctly authenticated all signals.
4 GPS_AUTHENTICATION_STATE_DISABLED GPS signal authentication is disabled on the receiver.

GPS_JAMMING_STATE — [WIP] {#GPS_JAMMING_STATE}

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

Signal jamming state in a GPS receiver.

Value Name Description
0 GPS_JAMMING_STATE_UNKNOWN The GPS receiver does not provide GPS signal jamming info.
1 GPS_JAMMING_STATE_OK The GPS receiver detected no signal jamming.
2 GPS_JAMMING_STATE_MITIGATED The GPS receiver detected and mitigated signal jamming.
3 GPS_JAMMING_STATE_DETECTED The GPS receiver detected signal jamming.

GPS_SPOOFING_STATE — [WIP] {#GPS_SPOOFING_STATE}

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

Signal spoofing state in a GPS receiver.

Value Name Description
0 GPS_SPOOFING_STATE_UNKNOWN The GPS receiver does not provide GPS signal spoofing info.
1 GPS_SPOOFING_STATE_OK The GPS receiver detected no signal spoofing.
2 GPS_SPOOFING_STATE_MITIGATED The GPS receiver detected and mitigated signal spoofing.
3 GPS_SPOOFING_STATE_DETECTED The GPS receiver detected signal spoofing but still has a fix.

GPS_RAIM_STATE — [WIP] {#GPS_RAIM_STATE}

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

State of RAIM processing.

Value Name Description
0 GPS_RAIM_STATE_UNKNOWN RAIM capability is unknown.
1 GPS_RAIM_STATE_DISABLED RAIM is disabled.
2 GPS_RAIM_STATE_OK RAIM integrity check was successful.
3 GPS_RAIM_STATE_FAILED RAIM integrity check failed.

Commands (MAV_CMD) {#mav_commands}

MAV_CMD_DO_FIGURE_EIGHT (35) — [WIP] {#MAV_CMD_DO_FIGURE_EIGHT}

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

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) Description Units
1 (Major Radius) 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.
m
2 (Minor Radius) 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.
m
3
4 (Orientation) Orientation 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/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.
6 (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.
7 (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.

MAV_CMD_DO_UPGRADE (247) — [WIP] {#MAV_CMD_DO_UPGRADE}

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

Request a target system to start an upgrade of one (or all) of its components.

For example, the command might be sent to a companion computer to cause it to upgrade a connected flight controller. The system doing the upgrade will report progress using the normal command protocol sequence for a long running operation. Command protocol information: https://mavlink.io/en/services/command.html.

Param (Label) Description Values
1 (Component ID) Component id of the component to be upgraded. If set to 0, all components should be upgraded. MAV_COMPONENT
2 (Reboot) 0: Do not reboot component after the action is executed, 1: Reboot component after the action is executed. min: 0 max: 1 inc: 1
3 Reserved
4 Reserved
5 Reserved
6 Reserved
7 WIP: upgrade progress report rate (can be used for more granular control).

MAV_CMD_DO_SET_STANDARD_MODE (262) — [WIP] {#MAV_CMD_DO_SET_STANDARD_MODE}

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

Enable the specified standard MAVLink mode.

If the mode is not supported the vehicle should ACK with MAV_RESULT_FAILED.

Param (Label) Description Values
1 (Standard Mode) The mode to set. MAV_STANDARD_MODE
2
3
4
5
6
7

MAV_CMD_SET_AT_S_PARAM (550) — [WIP] {#MAV_CMD_SET_AT_S_PARAM}

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

Allows setting an AT S command of an SiK radio.

Param (Label) Description
1 (Radio instance) The radio instance, one-based, 0 for all.
2 (Index) The Sx index, e.g. 3 for S3 which is NETID.
3 (Value) The value to set it to, e.g. default 25 for NETID
4
5
6
7

MAV_CMD_DO_SET_SYS_CMP_ID (610) — [WIP] {#MAV_CMD_DO_SET_SYS_CMP_ID}

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

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.

Param (Label) Description Values
1 (System ID) New system ID for target component(s). 0: ignore and reject command (broadcast system ID not allowed). min: 1 max: 255 inc: 1
2 (Component ID) New component ID for target component(s). 0: ignore (component IDs don't change). min: 0 max: 255 inc: 1
3 (Reboot) Reboot components after ID change. Any non-zero value triggers the reboot.
4

MAV_CMD_ODID_SET_EMERGENCY (12900) — [WIP] {#MAV_CMD_ODID_SET_EMERGENCY}

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

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.

Param (Label) Description Values
1 (Number) Set/unset emergency 0: unset, 1: set min: 0 inc: 1
2
3
4 Empty
5 Empty
5 Empty
6 Empty
7 Empty

MAV_CMD_REQUEST_OPERATOR_CONTROL (32100) — [WIP] {#MAV_CMD_REQUEST_OPERATOR_CONTROL}

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

Request GCS control of a system (or of a specific component in a system).

A controlled system should only accept MAVLink commands and command-like messages that are sent by its controlling GCS, or from other components with the same system id. Commands from other systems should be rejected with MAV_RESULT_FAILED (except for this command, which may be acknowledged with MAV_RESULT_ACCEPTED if control is granted). Command-like messages should be ignored (or rejected if that is supported by their associated protocol).

GCS control of the whole system is managed via a single component that we will refer to here as the "system manager component". This component streams the CONTROL_STATUS message and sets the GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER flag. Other components in the system should monitor for the CONTROL_STATUS message with this flag, and set their controlling GCS to match its published system id. A GCS that wants to control the system should also monitor for the same message and flag, and address the MAV_CMD_REQUEST_OPERATOR_CONTROL to its component id. Note that integrators are required to ensure that there is only one system manager component in the system (i.e. one component emitting the message with GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER set).

The MAV_CMD_REQUEST_OPERATOR_CONTROL command is sent by a GCS to the system manager component to request or release control of a system, specifying whether subsequent takeover requests from another GCS are automatically granted, or require permission.

The system manager component should grant control to the GCS if the system does not require takeover permission (or is uncontrolled) and ACK the request with MAV_RESULT_ACCEPTED. The system manager component should then stream CONTROL_STATUS indicating its controlling system: all other components with the same system id should monitor this message and set their own controlling GCS to match that of the system manager component.

If the system manager component cannot grant control (because takeover requires permission), the request should be rejected with MAV_RESULT_FAILED. The system manager component should then send this same command to the current owning GCS in order to notify of the request. The owning GCS would ACK with MAV_RESULT_ACCEPTED, and might choose to release control of the vehicle, or re-request control with the takeover bit set to allow permission. In case it choses to re-request control with takeover bit set to allow permission, requestor GCS will only have 10 seconds to get control, otherwise owning GCS will re-request control with takeover bit set to disallow permission, and requestor GCS will need repeat the request if still interested in getting control. Note that the pilots of both GCS should co-ordinate safe handover offline.

Note that in most systems the only controlled component will be the "system manager component", and that will be the autopilot. However separate GCS control of a particular component is also permitted, if supported by the component. In this case the GCS will address MAV_CMD_REQUEST_OPERATOR_CONTROL to the specific component it wants to control. The component will then stream CONTROL_STATUS for its controlling GCS (it must not set GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER). The component should fall back to the system GCS (if any) when it is not directly controlled, and may stop emitting CONTROL_STATUS. The flow is otherwise the same as for requesting control over the whole system.

Param (Label) Description Values Units
1 (Sysid requesting control) System ID of GCS requesting control. 0 when command sent from GCS to autopilot (autopilot determines requesting GCS sysid from message header). Sysid of GCS requesting control when command sent by autopilot to controlling GCS.
2 (Action) 0: Release control, 1: Request control.
3 (Allow takeover) Enable automatic granting of ownership on request (by default reject request and notify current owner). 0: Ask current owner and reject request, 1: Allow automatic takeover.
4 (Request timeout) Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control. min: 3 max: 60 s
5 Empty
6 Empty
7 Empty

MAV_CMD_EXTERNAL_WIND_ESTIMATE (43004) — [WIP] {#MAV_CMD_EXTERNAL_WIND_ESTIMATE}

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

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.

Param (Label) Description Values Units
1 (Wind speed) Horizontal wind speed. min: 0 m/s
2 (Wind speed accuracy) Estimated 1 sigma accuracy of wind speed. Set to NaN if unknown. m/s
3 (Direction) Azimuth (relative to true north) from where the wind is blowing. min: 0 max: 360 deg
4 (Direction accuracy) Estimated 1 sigma accuracy of wind direction. Set to NaN if unknown. deg
5 Empty
6 Empty
7 Empty