Available on crate feature
development
only.Expand description
This file was automatically generated, do not edit
Structs§
- ACTUATOR_
CONTROL_ TARGET_ DATA - id: 140 Set the vehicle attitude and body angular rates..
- ACTUATOR_
OUTPUT_ STATUS_ DATA - id: 375 The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW..
- ADSB_
VEHICLE_ DATA - id: 246 The location and information of an ADSB vehicle.
- AIRSPEED_
DATA - id: 295 Airspeed information from a sensor..
- AIS_
VESSEL_ DATA - id: 301 The location and information of an AIS vessel.
- ALTITUDE_
DATA - id: 141 The current system altitude..
- ATTITUDE_
DATA - id: 30 The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)..
- ATTITUDE_
QUATERNION_ COV_ DATA - id: 61 The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)..
- ATTITUDE_
QUATERNION_ DATA - id: 31 The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)..
- ATTITUDE_
TARGET_ DATA - id: 83 Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way..
- ATT_
POS_ MOCAP_ DATA - id: 138 Motion capture attitude and position.
- AUTH_
KEY_ DATA - id: 7 Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety..
- AUTOPILOT_
STATE_ FOR_ GIMBAL_ DEVICE_ DATA - id: 286 Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device’s estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis..
- AUTOPILOT_
VERSION_ DATA - id: 148 Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE..
- AVAILABLE_
MODES_ DATA - id: 435 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)..
- Adsb
Flags - These flags indicate status such as data validity of each data source. Set = data valid
- AisFlags
- These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid.
- Attitude
Target Typemask - Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored.
- BATTERY_
STATUS_ DATA - id: 147 Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send SMART_BATTERY_INFO..
- BATTERY_
STATUS_ V2_ DATA - id: 369 Battery dynamic information. This should be streamed (nominally at 1Hz). Static/invariant battery information is sent in SMART_BATTERY_INFO. Note that smart batteries should set the MAV_BATTERY_STATUS_FLAGS_CAPACITY_RELATIVE_TO_FULL bit to indicate that supplied capacity values are relative to a battery that is known to be full. Power monitors would not set this bit, indicating that capacity_consumed is relative to drone power-on, and that other values are estimated based on the assumption that the battery was full on power-on..
- BUTTON_
CHANGE_ DATA - id: 257 Report button state change..
- CAMERA_
CAPTURE_ STATUS_ DATA - id: 262 Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command..
- CAMERA_
FOV_ STATUS_ DATA - id: 271 Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command..
- CAMERA_
IMAGE_ CAPTURED_ DATA - id: 263 Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range..
- CAMERA_
INFORMATION_ DATA - id: 259 Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command..
- CAMERA_
SETTINGS_ DATA - id: 260 Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command..
- CAMERA_
TRACKING_ GEO_ STATUS_ DATA - id: 276 Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval..
- CAMERA_
TRACKING_ IMAGE_ STATUS_ DATA - id: 275 Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval..
- CAMERA_
TRIGGER_ DATA - id: 112 Camera-IMU triggering and synchronisation message..
- CANFD_
FRAME_ DATA - id: 387 A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling).
- CAN_
FILTER_ MODIFY_ DATA - id: 388 Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages..
- CAN_
FRAME_ DATA - id: 386 A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD..
- CELLULAR_
CONFIG_ DATA - id: 336 Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE..
- CELLULAR_
STATUS_ DATA - id: 334 Report current used cellular network status.
- CHANGE_
OPERATOR_ CONTROL_ ACK_ DATA - id: 6 Accept / deny control of this MAV.
- CHANGE_
OPERATOR_ CONTROL_ DATA - id: 5 Request to control this MAV.
- COLLISION_
DATA - id: 247 Information about a potential collision.
- COMMAND_
ACK_ DATA - id: 77 Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html.
- COMMAND_
CANCEL_ DATA - id: 80 Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html.
- COMMAND_
INT_ DATA - id: 75 Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG when sending positional data in params 5 and 6, as it allows for greater precision when sending latitudes/longitudes. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component’s current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html.
- COMMAND_
LONG_ DATA - id: 76 Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands where param 5 and param 6 contain latitude/longitude data, as sending these in floats can result in a significant loss of precision. COMMAND_LONG is required for commands that mandate float values in params 5 and 6. The command microservice is documented at https://mavlink.io/en/services/command.html.
- COMPONENT_
INFORMATION_ BASIC_ DATA - id: 396 Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required..
- COMPONENT_
INFORMATION_ DATA - id: 395 Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE..
- COMPONENT_
METADATA_ DATA - id: 397 Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component’s general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: https://mavlink.io/en/services/component_information.html. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION..
- CONTROL_
SYSTEM_ STATE_ DATA - id: 146 The smoothed, monotonic system state used to feed the control loops of the system..
- CURRENT_
EVENT_ SEQUENCE_ DATA - id: 411 Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events..
- CURRENT_
MODE_ DATA - id: 436 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..
- Camera
CapFlags - Camera capability flags (Bitmap)
- DATA_
STREAM_ DATA - id: 67 Data stream status information..
- DATA_
TRANSMISSION_ HANDSHAKE_ DATA - id: 130 Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html..
- DEBUG_
DATA - id: 254 Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N..
- DEBUG_
FLOAT_ ARRAY_ DATA - id: 350 Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code..
- DEBUG_
VECT_ DATA - id: 250 To debug something using a named 3D vector..
- DISTANCE_
SENSOR_ DATA - id: 132 Distance sensor information for an onboard rangefinder..
- EFI_
STATUS_ DATA - id: 225 EFI status output.
- ENCAPSULATED_
DATA_ DATA - id: 131 Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html..
- ESC_
INFO_ DATA - id: 290 ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data..
- ESC_
STATUS_ DATA - id: 291 ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)..
- ESTIMATOR_
STATUS_ DATA - id: 230 Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user..
- EVENT_
DATA - id: 410 Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)..
- EXTENDED_
SYS_ STATE_ DATA - id: 245 Provides state for additional features.
- EscFailure
Flags - Flags to report ESC failures.
- Estimator
Status Flags - Flags in ESTIMATOR_STATUS message
- FENCE_
STATUS_ DATA - id: 162 Status of geo-fencing. Sent in extended status stream when fencing enabled..
- FIGURE_
EIGHT_ EXECUTION_ STATUS_ DATA - id: 361 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..
- FILE_
TRANSFER_ PROTOCOL_ DATA - id: 110 File transfer protocol message: https://mavlink.io/en/services/ftp.html..
- FLIGHT_
INFORMATION_ DATA - id: 264 Information about flight since last arming. This can be requested using MAV_CMD_REQUEST_MESSAGE..
- FOLLOW_
TARGET_ DATA - id: 144 Current motion information from a designated system.
- GENERATOR_
STATUS_ DATA - id: 373 Telemetry of power generation system. Alternator or mechanical generator..
- GIMBAL_
DEVICE_ ATTITUDE_ STATUS_ DATA - id: 285 Message reporting the status of a gimbal device. This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Other conditions of the flags are not allowed. The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN..
- GIMBAL_
DEVICE_ INFORMATION_ DATA - id: 283 Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc…
- GIMBAL_
DEVICE_ SET_ ATTITUDE_ DATA - id: 284 Low level message to control a gimbal device’s attitude. This message is to be sent from the gimbal manager to the gimbal device component. The quaternion and angular velocities can be set to NaN according to use case. For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. These rules are to ensure backwards compatibility. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME..
- GIMBAL_
MANAGER_ INFORMATION_ DATA - id: 280 Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE..
- GIMBAL_
MANAGER_ SET_ ATTITUDE_ DATA - id: 282 High level message to control a gimbal’s attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case..
- GIMBAL_
MANAGER_ SET_ MANUAL_ CONTROL_ DATA - id: 288 High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case..
- GIMBAL_
MANAGER_ SET_ PITCHYAW_ DATA - id: 287 High level message to control a gimbal’s pitch and yaw angles. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case..
- GIMBAL_
MANAGER_ STATUS_ DATA - id: 281 Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)..
- GLOBAL_
POSITION_ INT_ COV_ DATA - id: 63 The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset..
- GLOBAL_
POSITION_ INT_ DATA - id: 33 The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient..
- GLOBAL_
VISION_ POSITION_ ESTIMATE_ DATA - id: 101 Global position/attitude estimate from a vision source..
- GPS2_
RAW_ DATA - id: 124 Second GPS data..
- GPS2_
RTK_ DATA - id: 128 RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting.
- GPS_
GLOBAL_ ORIGIN_ DATA - id: 49 Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message..
- GPS_
INJECT_ DATA_ DATA - id: 123 Data for injecting into the onboard GPS (used for DGPS).
- GPS_
INPUT_ DATA - id: 232 GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system..
- GPS_
RAW_ INT_ DATA - id: 24 The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate..
- GPS_
RTCM_ DATA_ DATA - id: 233 RTCM message for injecting into the onboard GPS (used for DGPS).
- GPS_
RTK_ DATA - id: 127 RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting.
- GPS_
STATUS_ DATA - id: 25 The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites..
- GROUP_
END_ DATA - id: 415 Emitted during mission execution when control reaches MAV_CMD_GROUP_END..
- GROUP_
START_ DATA - id: 414 Emitted during mission execution when control reaches MAV_CMD_GROUP_START..
- Gimbal
Device CapFlags - Gimbal device (low level) capability flags (bitmap).
- Gimbal
Device Error Flags - Gimbal device (low level) error flags (bitmap, 0 means no error)
- Gimbal
Device Flags - Flags for gimbal device (lower level) operation.
- Gimbal
Manager CapFlags - Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags.
- GpsInput
Ignore Flags - HEARTBEAT_
DATA - id: 0 The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html.
- HIGHRES_
IMU_ DATA - id: 105 The IMU readings in SI units in NED body frame.
- HIGH_
LATENC Y2_ DATA - id: 235 Message appropriate for high latency connections like Iridium (version 2).
- HIGH_
LATENCY_ DATA - id: 234 Message appropriate for high latency connections like Iridium.
- HIL_
ACTUATOR_ CONTROLS_ DATA - id: 93 Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS).
- HIL_
CONTROLS_ DATA - id: 91 Sent from autopilot to simulation. Hardware in the loop control outputs.
- HIL_
GPS_ DATA - id: 113 The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate..
- HIL_
OPTICAL_ FLOW_ DATA - id: 114 Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor).
- HIL_
RC_ INPUTS_ RAW_ DATA - id: 92 Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification..
- HIL_
SENSOR_ DATA - id: 107 The IMU readings in SI units in NED body frame.
- HIL_
STATE_ DATA - id: 90 Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations..
- HIL_
STATE_ QUATERNION_ DATA - id: 115 Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations..
- HOME_
POSITION_ DATA - id: 242 Contains the home position. The home position is the default position that the system will return to and land on. The position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)..
- HYGROMETER_
SENSOR_ DATA - id: 12920 Temperature and humidity from hygrometer..
- Highres
ImuUpdated Flags - Flags in the HIGHRES_IMU message indicate which fields have updated since the last message
- HilSensor
Updated Flags - Flags in the HIL_SENSOR message indicate which fields have updated since the last message
- HlFailure
Flag - Flags to report failure cases over the high latency telemtry.
- ISBD_
LINK_ STATUS_ DATA - id: 335 Status of the Iridium SBD link..
- LANDING_
TARGET_ DATA - id: 149 The location of a landing target. See: https://mavlink.io/en/services/landing_target.html.
- LINK_
NODE_ STATUS_ DATA - id: 8 Status generated in each node in the communication chain and injected into MAVLink stream..
- LOCAL_
POSITION_ NED_ COV_ DATA - id: 64 The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention).
- LOCAL_
POSITION_ NED_ DATA - id: 32 The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention).
- LOCAL_
POSITION_ NED_ SYSTEM_ GLOBAL_ OFFSET_ DATA - id: 89 The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention).
- LOGGING_
ACK_ DATA - id: 268 An ack for a LOGGING_DATA_ACKED message.
- LOGGING_
DATA_ ACKED_ DATA - id: 267 A message containing logged data which requires a LOGGING_ACK to be sent back.
- LOGGING_
DATA_ DATA - id: 266 A message containing logged data (see also MAV_CMD_LOGGING_START).
- LOG_
DATA_ DATA - id: 120 Reply to LOG_REQUEST_DATA.
- LOG_
ENTRY_ DATA - id: 118 Reply to LOG_REQUEST_LIST.
- LOG_
ERASE_ DATA - id: 121 Erase all logs.
- LOG_
REQUEST_ DATA_ DATA - id: 119 Request a chunk of a log.
- LOG_
REQUEST_ END_ DATA - id: 122 Stop log transfer and resume normal logging.
- LOG_
REQUEST_ LIST_ DATA - id: 117 Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0..
- MAG_
CAL_ REPORT_ DATA - id: 192 Reports results of completed compass calibration. Sent until MAG_CAL_ACK received..
- MANUAL_
CONTROL_ DATA - id: 69 This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask.
- MANUAL_
SETPOINT_ DATA - id: 81 Setpoint in roll, pitch, yaw and thrust from the operator.
- MEMORY_
VECT_ DATA - id: 249 Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output..
- MESSAGE_
INTERVAL_ DATA - id: 244 The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. This interface replaces DATA_STREAM..
- MISSION_
ACK_ DATA - id: 47 Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)..
- MISSION_
CHECKSUM_ DATA - id: 53 Checksum for the current mission, rally point or geofence plan, or for the “combined” plan (a GCS can use these checksums to determine if it has matching plans). This message must be broadcast with the appropriate checksum following any change to a mission, geofence or rally point definition (immediately after the MISSION_ACK that completes the upload sequence). It may also be requested using MAV_CMD_REQUEST_MESSAGE, where param 2 indicates the plan type for which the checksum is required. The checksum must be calculated on the autopilot, but may also be calculated by the GCS. The checksum uses the same CRC32 algorithm as MAVLink FTP (https://mavlink.io/en/services/ftp.html#crc32-implementation). The checksum for a mission, geofence or rally point definition is run over each item in the plan in seq order (excluding the home location if present in the plan), and covers the following fields (in order): frame, command, autocontinue, param1, param2, param3, param4, param5, param6, param7. The checksum for the whole plan (MAV_MISSION_TYPE_ALL) is calculated using the same approach, running over each sub-plan in the following order: mission, geofence then rally point..
- MISSION_
CLEAR_ ALL_ DATA - id: 45 Delete all mission items at once..
- MISSION_
COUNT_ DATA - id: 44 This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints..
- MISSION_
CURRENT_ DATA - id: 42 Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT..
- MISSION_
ITEM_ DATA - id: 39 Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system’s current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html..
- MISSION_
ITEM_ INT_ DATA - id: 73 Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component’s current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html..
- MISSION_
ITEM_ REACHED_ DATA - id: 46 A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint..
- MISSION_
REQUEST_ DATA - id: 40 Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html.
- MISSION_
REQUEST_ INT_ DATA - id: 51 Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html.
- MISSION_
REQUEST_ LIST_ DATA - id: 43 Request the overall list of mission items from the system/component..
- MISSION_
REQUEST_ PARTIAL_ LIST_ DATA - id: 37 Request a partial list of mission items from the system/component. https://mavlink.io/en/services/mission.html. If start and end index are the same, just send one waypoint..
- MISSION_
SET_ CURRENT_ DATA - id: 41 Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode..
- MISSION_
WRITE_ PARTIAL_ LIST_ DATA - id: 38 This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!.
- MOUNT_
ORIENTATION_ DATA - id: 265 Orientation of a mount.
- MavBattery
Fault - Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set.
- MavBattery
Status Flags - Battery status flags for fault, health and state indication.
- MavEvent
Current Sequence Flags - Flags for CURRENT_EVENT_SEQUENCE.
- MavGenerator
Status Flag - Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).
- MavMode
Flag - These flags encode the MAV mode.
- MavPower
Status - Power supply status flags (bitmask)
- MavProtocol
Capability - Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.
- MavSys
Status Sensor - These encode the sensors whose status is sent as part of the SYS_STATUS message.
- MavSys
Status Sensor Extended - These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields.
- MavWinch
Status Flag - Winch status flags used in WINCH_STATUS
- NAMED_
VALUE_ FLOAT_ DATA - id: 251 Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output..
- NAMED_
VALUE_ INT_ DATA - id: 252 Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output..
- NAV_
CONTROLLER_ OUTPUT_ DATA - id: 62 The state of the navigation and position controller..
- OBSTACLE_
DISTANCE_ DATA - id: 330 Obstacle distances in front of the sensor, starting from the left in increment degrees to the right.
- ODOMETRY_
DATA - id: 331 Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html)..
- ONBOARD_
COMPUTER_ STATUS_ DATA - id: 390 Hardware status sent by an onboard computer..
- OPEN_
DRONE_ ID_ ARM_ STATUS_ DATA - id: 12918 Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm..
- OPEN_
DRONE_ ID_ AUTHENTICATION_ DATA - id: 12902 Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes..
- OPEN_
DRONE_ ID_ BASIC_ ID_ DATA - id: 12900 Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html..
- OPEN_
DRONE_ ID_ LOCATION_ DATA - id: 12901 Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft..
- OPEN_
DRONE_ ID_ MESSAGE_ PACK_ DATA - id: 12915 An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon..
- OPEN_
DRONE_ ID_ OPERATOR_ ID_ DATA - id: 12905 Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID..
- OPEN_
DRONE_ ID_ SELF_ ID_ DATA - id: 12903 Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation..
- OPEN_
DRONE_ ID_ SYSTEM_ DATA - id: 12904 Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information..
- OPEN_
DRONE_ ID_ SYSTEM_ UPDATE_ DATA - id: 12919 Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location..
- OPTICAL_
FLOW_ DATA - id: 100 Optical flow from a flow sensor (e.g. optical mouse sensor).
- OPTICAL_
FLOW_ RAD_ DATA - id: 106 Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor).
- ORBIT_
EXECUTION_ STATUS_ DATA - id: 360 Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)..
- PARAM_
ACK_ TRANSACTION_ DATA - id: 19 Response from a PARAM_SET message when it is used in a transaction..
- PARAM_
EXT_ ACK_ DATA - id: 324 Response from a PARAM_EXT_SET message..
- PARAM_
EXT_ REQUEST_ LIST_ DATA - id: 321 Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE..
- PARAM_
EXT_ REQUEST_ READ_ DATA - id: 320 Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response..
- PARAM_
EXT_ SET_ DATA - id: 323 Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response..
- PARAM_
EXT_ VALUE_ DATA - id: 322 Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout..
- PARAM_
MAP_ RC_ DATA - id: 50 Bind a RC channel to a parameter. The parameter should change according to the RC channel value..
- PARAM_
REQUEST_ LIST_ DATA - id: 21 Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html.
- PARAM_
REQUEST_ READ_ DATA - id: 20 Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code..
- PARAM_
SET_ DATA - id: 23 Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received..
- PARAM_
VALUE_ DATA - id: 22 Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html.
- PING_
DATA - id: 4 A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html.
- PLAY_
TUNE_ DATA - id: 258 Control vehicle tone generation (buzzer)..
- PLAY_
TUNE_ V2_ DATA - id: 400 Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE..
- POSITION_
TARGET_ GLOBAL_ INT_ DATA - id: 87 Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way..
- POSITION_
TARGET_ LOCAL_ NED_ DATA - id: 85 Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way..
- POWER_
STATUS_ DATA - id: 125 Power supply status.
- PROTOCOL_
VERSION_ DATA - id: 300 Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly..
- Position
Target Typemask - Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration.
- RADIO_
STATUS_ DATA - id: 109 Status generated by radio and injected into MAVLink stream..
- RAW_
IMU_ DATA - id: 27 The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging..
- RAW_
PRESSURE_ DATA - id: 28 The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values..
- RAW_
RPM_ DATA - id: 339 RPM sensor data message..
- RC_
CHANNELS_ DATA - id: 65 The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification..
- RC_
CHANNELS_ OVERRIDE_ DATA - id: 70 The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels.
- RC_
CHANNELS_ RAW_ DATA - id: 35 The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification..
- RC_
CHANNELS_ SCALED_ DATA - id: 34 The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX..
- REQUEST_
DATA_ STREAM_ DATA - id: 66 Request a data stream..
- REQUEST_
EVENT_ DATA - id: 412 Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response..
- RESOURCE_
REQUEST_ DATA - id: 142 The autopilot is requesting a resource (file, binary, other type of data).
- RESPONSE_
EVENT_ ERROR_ DATA - id: 413 Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)..
- SAFETY_
ALLOWED_ AREA_ DATA - id: 55 Read out the safety zone the MAV currently assumes..
- SAFETY_
SET_ ALLOWED_ AREA_ DATA - id: 54 Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations..
- SCALED_
IMU2_ DATA - id: 116 The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units.
- SCALED_
IMU3_ DATA - id: 129 The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units.
- SCALED_
IMU_ DATA - id: 26 The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units.
- SCALED_
PRESSUR E2_ DATA - id: 137 Barometer readings for 2nd barometer.
- SCALED_
PRESSUR E3_ DATA - id: 143 Barometer readings for 3rd barometer.
- SCALED_
PRESSURE_ DATA - id: 29 The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field..
- SERIAL_
CONTROL_ DATA - id: 126 Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate..
- SERVO_
OUTPUT_ RAW_ DATA - id: 36 Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%..
- SETUP_
SIGNING_ DATA - id: 256 Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing.
- SET_
ACTUATOR_ CONTROL_ TARGET_ DATA - id: 139 Set the vehicle attitude and body angular rates..
- SET_
ATTITUDE_ TARGET_ DATA - id: 82 Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)..
- SET_
GPS_ GLOBAL_ ORIGIN_ DATA - id: 48 Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor..
- SET_
HOME_ POSITION_ DATA - id: 243 Sets the home position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)..
- SET_
MODE_ DATA - id: 11 Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component..
- SET_
POSITION_ TARGET_ GLOBAL_ INT_ DATA - id: 86 Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)..
- SET_
POSITION_ TARGET_ LOCAL_ NED_ DATA - id: 84 Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)..
- SIM_
STATE_ DATA - id: 108 Status of simulation environment, if used.
- SMART_
BATTERY_ INFO_ DATA - id: 370 Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for smart battery frequent updates..
- STATUSTEXT_
DATA - id: 253 Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)..
- STORAGE_
INFORMATION_ DATA - id: 261 Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc..
- SUPPORTED_
TUNES_ DATA - id: 401 Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE..
- SYSTEM_
TIME_ DATA - id: 2 The system time is the time of the master clock, typically the computer clock of the main onboard computer..
- SYS_
STATUS_ DATA - id: 1 The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout..
- Serial
Control Flag - SERIAL_CONTROL flags (bitmask)
- TARGET_
ABSOLUTE_ DATA - id: 510 Current motion information from sensors on a target.
- TARGET_
RELATIVE_ DATA - id: 511 The location of a target measured by MAV’s onboard sensors..
- TERRAIN_
CHECK_ DATA - id: 135 Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission..
- TERRAIN_
DATA_ DATA - id: 134 Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html.
- TERRAIN_
REPORT_ DATA - id: 136 Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html.
- TERRAIN_
REQUEST_ DATA - id: 133 Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html.
- TIMESYNC_
DATA - id: 111
Time synchronization message. The message is used for both timesync requests and responses. The request is sent with
ts1=syncing component timestamp
andtc1=0
, and may be broadcast or targeted to a specific system/component. The response is sent withts1=syncing component timestamp
(mirror back unchanged), andtc1=responding component timestamp
, with thetarget_system
andtarget_component
set to ids of the original request. Systems can determine if they are receiving a request or response based on the value oftc
. If the response hastarget_system==target_component==0
the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn’t matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset.. - TIME_
ESTIMATE_ TO_ TARGET_ DATA - id: 380 Time/duration estimates for various events and actions given the current vehicle state and position..
- TRAJECTORY_
REPRESENTATION_ BEZIER_ DATA - id: 333 Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)..
- TRAJECTORY_
REPRESENTATION_ WAYPOINTS_ DATA - id: 332 Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)..
- TUNNEL_
DATA - id: 385 Message for transporting “arbitrary” variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification..
- Target
Absolute Sensor Capability Flags - These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.
- Tune
Format - Tune formats (used for vehicle buzzer/tone generation).
- UAVCAN_
NODE_ INFO_ DATA - id: 311 General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service “uavcan.protocol.GetNodeInfo” for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at http://uavcan.org..
- UAVCAN_
NODE_ STATUS_ DATA - id: 310 General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message “uavcan.protocol.NodeStatus” for the background information. The UAVCAN specification is available at http://uavcan.org..
- UTM_
GLOBAL_ POSITION_ DATA - id: 340 The global position resulting from GPS and sensor fusion..
- UtmData
Avail Flags - Flags for the global position report.
- V2_
EXTENSION_ DATA - id: 248 Message implementing parts of the V2 payload specs in V1 frames for transitional support..
- VFR_
HUD_ DATA - id: 74 Metrics typically displayed on a HUD for fixed wing aircraft..
- VIBRATION_
DATA - id: 241 Vibration levels and accelerometer clipping.
- VICON_
POSITION_ ESTIMATE_ DATA - id: 104 Global position estimate from a Vicon motion system source..
- VIDEO_
STREAM_ INFORMATION_ DATA - id: 269 Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc..
- VIDEO_
STREAM_ STATUS_ DATA - id: 270 Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE..
- VISION_
POSITION_ ESTIMATE_ DATA - id: 102 Local position/attitude estimate from a vision source..
- VISION_
SPEED_ ESTIMATE_ DATA - id: 103 Speed estimate from a vision source..
- WHEEL_
DISTANCE_ DATA - id: 9000 Cumulative distance traveled for each reported wheel..
- WIFI_
CONFIG_ AP_ DATA - id: 299 Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE.
- WIFI_
NETWORK_ INFO_ DATA - id: 298 Detected WiFi network status information. This message is sent per each WiFi network detected in range with known SSID and general status parameters..
- WINCH_
STATUS_ DATA - id: 9005 Winch status..
- WIND_
COV_ DATA - id: 231 Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)..
Enums§
- Actuator
Configuration - Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.
- Actuator
Output Function - Actuator output function. Values greater or equal to 1000 are autopilot-specific.
- Adsb
Altitude Type - Enumeration of the ADSB altimeter types
- Adsb
Emitter Type - ADSB classification for the type of vehicle emitting the transponder signal
- Airspeed
Sensor Flags - Airspeed sensor flags
- AisNav
Status - Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html
- AisType
- Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html
- Autotune
Axis - Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.
- Camera
Mode - Camera Modes.
- Camera
Tracking Mode - Camera tracking modes
- Camera
Tracking Status Flags - Camera tracking status flags
- Camera
Tracking Target Data - Camera tracking target data (shows where tracked target is within image)
- Camera
Zoom Type - Zoom types for MAV_CMD_SET_CAMERA_ZOOM
- CanFilter
Op - Cellular
Config Response - Possible responses from a CELLULAR_CONFIG message.
- Cellular
Network Failed Reason - These flags are used to diagnose the failure state of CELLULAR_STATUS
- Cellular
Network Radio Type - Cellular network radio type
- Cellular
Status Flag - These flags encode the cellular network status
- Comp
Metadata Type - Supported component metadata types. These are used in the “general” metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages.
- EscConnection
Type - Indicates the ESC connection type.
- Failure
Type - List of possible failure type to inject.
- Failure
Unit - List of possible units where failures can be injected.
- Fence
Action - Actions following geofence breach.
- Fence
Breach - Fence
Mitigate - Actions being taken to mitigate/prevent fence breach
- Firmware
Version Type - These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65.
- Gimbal
Manager Flags - Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.
- GpsFix
Type - Type of GPS fix
- Gripper
Actions - Gripper actions.
- Landing
Target Type - Type of landing target
- MagCal
Status - MavArm
Auth Denied Reason - MavAutopilot
- Micro air vehicle / autopilot classes. This identifies the individual model.
- MavBattery
Charge State - Enumeration for battery charge states.
- MavBattery
Function - Enumeration of battery functions
- MavBattery
Mode - Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight.
- MavBattery
Type - Enumeration of battery types
- MavCmd
- 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
- MavCmd
Ack - ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.
- MavCollision
Action - Possible actions an aircraft can take to avoid a collision.
- MavCollision
Src - Source of information about this collision.
- MavCollision
Threat Level - Aircraft-rated danger from this threat.
- MavComponent
- Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.
- MavData
Stream - A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages.
- MavDistance
Sensor - Enumeration of distance sensor types
- MavDo
Reposition Flags - Bitmap of options for the MAV_CMD_DO_REPOSITION
- MavEstimator
Type - Enumeration of estimator types
- MavEvent
Error Reason - Reason for an event error response.
- MavFrame
- Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - “GLOBAL”: Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with “GLOBAL”: - “RELATIVE_ALT”: Altitude is relative to the vehicle home position rather than MSL. - “TERRAIN_ALT”: Altitude is relative to ground level rather than MSL. - “INT”: Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - “LOCAL”: Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (“EKF”). - “BODY”: Origin of local frame travels with the vehicle. NOTE, “BODY” does NOT indicate alignment of frame axis with vehicle attitude. - “OFFSET”: Deprecated synonym for “BODY” (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).
- MavFtp
Err - MAV FTP error codes (https://mavlink.io/en/services/ftp.html)
- MavFtp
Opcode - MAV FTP opcodes: https://mavlink.io/en/services/ftp.html
- MavGoto
- Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.
- MavLanded
State - Enumeration of landed detector states
- MavMessage
- MavMission
Result - Result of mission operation (in a MISSION_ACK message).
- MavMission
Type - Type of mission items being requested/sent in mission protocol.
- MavMode
- These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.
- MavMode
Flag Decode Position - These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.
- MavMount
Mode - Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.
- MavOdid
ArmStatus - MavOdid
Auth Type - MavOdid
Category Eu - MavOdid
Class Eu - MavOdid
Classification Type - MavOdid
Desc Type - MavOdid
Height Ref - MavOdid
HorAcc - MavOdid
IdType - MavOdid
Operator IdType - MavOdid
Operator Location Type - MavOdid
Speed Acc - MavOdid
Status - MavOdid
Time Acc - MavOdid
UaType - MavOdid
VerAcc - MavParam
ExtType - Specifies the datatype of a MAVLink extended parameter.
- MavParam
Type - Specifies the datatype of a MAVLink parameter.
- MavResult
- Result from a MAVLink command (MAV_CMD)
- MavRoi
- The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI).
- MavSensor
Orientation - Enumeration of sensor orientation, according to its rotations
- MavSeverity
- Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.
- MavStandard
Mode - 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.
- MavState
- MavTunnel
Payload Type - MavType
- MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).
- MavVtol
State - Enumeration of VTOL states
- Mavlink
Data Stream Type - Mission
State - States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles.
- Motor
Test Order - Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST.
- Motor
Test Throttle Type - Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST.
- NavVtol
Land Options - Orbit
YawBehaviour - Yaw behaviour during orbit flight.
- Parachute
Action - Parachute actions. Trigger release and enable/disable auto-release.
- Param
Ack - Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).
- Param
Transaction Action - Possible parameter transaction actions.
- Param
Transaction Transport - Possible transport layers to set and get parameters via mavlink during a parameter transaction.
- Precision
Land Mode - Precision land modes (used in MAV_CMD_NAV_LAND).
- Preflight
Storage Mission Action - Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)
- Preflight
Storage Parameter Action - Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)
- RcType
- RC type
- RtkBaseline
Coordinate System - RTK GPS baseline coordinate system, used for RTK corrections
- Serial
Control Dev - SERIAL_CONTROL device types
- SetFocus
Type - Focus types for MAV_CMD_SET_CAMERA_FOCUS
- Storage
Status - Flags to indicate the status of camera storage.
- Storage
Type - Flags to indicate the type of storage.
- Storage
Usage Flag - Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).
- Target
ObsFrame - The frame of a target observation from an onboard sensor.
- Uavcan
Node Health - Generalized UAVCAN node health
- Uavcan
Node Mode - Generalized UAVCAN node mode
- UtmFlight
State - Airborne status of UAS.
- Video
Stream Status Flags - Stream status flags (Bitmap)
- Video
Stream Type - Video stream types
- Vtol
Transition Heading - Direction of VTOL transition
- Wifi
Config ApMode - WiFi Mode.
- Wifi
Config ApResponse - Possible responses from a WIFI_CONFIG_AP message.
- Wifi
Network Security - WiFi wireless security protocols.
- Winch
Actions - Winch actions.