MAVLINK Common Message Set

These messages define the common message set, which is the reference message set implemented by most ground control stations and autopilots.

This is a human-readable form of the XML definition file: common.xml.

MAVLink 2 messages have an ID > 255 and are marked up using (MAVLink 2) in their description.

MAVLink 2 extension fields that have been added to MAVLink 1 messages are displayed in blue.

The current MAVLink version is 2.3. The minor version numbers (after the dot) range from 1-255.

This file has protocol dialect: 0.

MAV_AUTOPILOT

Micro air vehicle / autopilot classes. This identifies the individual model.

ValueField NameDescription
0MAV_AUTOPILOT_GENERICGeneric autopilot, full support for everything
1MAV_AUTOPILOT_RESERVEDReserved for future use.
2MAV_AUTOPILOT_SLUGSSLUGS autopilot, http://slugsuav.soe.ucsc.edu
3MAV_AUTOPILOT_ARDUPILOTMEGAArduPilot - Plane/Copter/Rover/Sub/Tracker, http://ardupilot.org
4MAV_AUTOPILOT_OPENPILOTOpenPilot, http://openpilot.org
5MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLYGeneric autopilot only supporting simple waypoints
6MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLYGeneric autopilot supporting waypoints and other simple navigation commands
7MAV_AUTOPILOT_GENERIC_MISSION_FULLGeneric autopilot supporting the full mission command set
8MAV_AUTOPILOT_INVALIDNo valid autopilot, e.g. a GCS or other MAVLink component
9MAV_AUTOPILOT_PPZPPZ UAV - http://nongnu.org/paparazzi
10MAV_AUTOPILOT_UDBUAV Dev Board
11MAV_AUTOPILOT_FPFlexiPilot
12MAV_AUTOPILOT_PX4PX4 Autopilot - http://px4.io/
13MAV_AUTOPILOT_SMACCMPILOTSMACCMPilot - http://smaccmpilot.org
14MAV_AUTOPILOT_AUTOQUADAutoQuad -- http://autoquad.org
15MAV_AUTOPILOT_ARMAZILAArmazila -- http://armazila.com
16MAV_AUTOPILOT_AEROBAerob -- http://aerob.ru
17MAV_AUTOPILOT_ASLUAVASLUAV autopilot -- http://www.asl.ethz.ch
18MAV_AUTOPILOT_SMARTAPSmartAP Autopilot - http://sky-drones.com
19MAV_AUTOPILOT_AIRRAILSAirRails - http://uaventure.com

MAV_TYPE

MAVLINK system type. All components in a system should report this type in their HEARTBEAT.

ValueField NameDescription
0MAV_TYPE_GENERICGeneric micro air vehicle.
1MAV_TYPE_FIXED_WINGFixed wing aircraft.
2MAV_TYPE_QUADROTORQuadrotor
3MAV_TYPE_COAXIALCoaxial helicopter
4MAV_TYPE_HELICOPTERNormal helicopter with tail rotor.
5MAV_TYPE_ANTENNA_TRACKERGround installation
6MAV_TYPE_GCSOperator control unit / ground control station
7MAV_TYPE_AIRSHIPAirship, controlled
8MAV_TYPE_FREE_BALLOONFree balloon, uncontrolled
9MAV_TYPE_ROCKETRocket
10MAV_TYPE_GROUND_ROVERGround rover
11MAV_TYPE_SURFACE_BOATSurface vessel, boat, ship
12MAV_TYPE_SUBMARINESubmarine
13MAV_TYPE_HEXAROTORHexarotor
14MAV_TYPE_OCTOROTOROctorotor
15MAV_TYPE_TRICOPTERTricopter
16MAV_TYPE_FLAPPING_WINGFlapping wing
17MAV_TYPE_KITEKite
18MAV_TYPE_ONBOARD_CONTROLLEROnboard companion controller
19MAV_TYPE_VTOL_DUOROTORTwo-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
20MAV_TYPE_VTOL_QUADROTORQuad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
21MAV_TYPE_VTOL_TILTROTORTiltrotor VTOL
22MAV_TYPE_VTOL_RESERVED2VTOL reserved 2
23MAV_TYPE_VTOL_RESERVED3VTOL reserved 3
24MAV_TYPE_VTOL_RESERVED4VTOL reserved 4
25MAV_TYPE_VTOL_RESERVED5VTOL reserved 5
26MAV_TYPE_GIMBALOnboard gimbal
27MAV_TYPE_ADSBADSB system (standalone)
28MAV_TYPE_PARAFOILSteerable, nonrigid airfoil
29MAV_TYPE_DODECAROTORDodecarotor
30MAV_TYPE_CAMERACamera (standalone)
31MAV_TYPE_CHARGING_STATIONCharging station
32MAV_TYPE_FLARMFLARM collision avoidance system (standalone)

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.

ValueField NameDescription
0FIRMWARE_VERSION_TYPE_DEVdevelopment release
64FIRMWARE_VERSION_TYPE_ALPHAalpha release
128FIRMWARE_VERSION_TYPE_BETAbeta release
192FIRMWARE_VERSION_TYPE_RCrelease candidate
255FIRMWARE_VERSION_TYPE_OFFICIALofficial stable release

HL_FAILURE_FLAG

Flags to report failure cases over the high latency telemtry.

ValueField NameDescription
1HL_FAILURE_FLAG_GPSGPS failure.
2HL_FAILURE_FLAG_DIFFERENTIAL_PRESSUREDifferential pressure sensor failure.
4HL_FAILURE_FLAG_ABSOLUTE_PRESSUREAbsolute pressure sensor failure.
8HL_FAILURE_FLAG_3D_ACCELAccelerometer sensor failure.
16HL_FAILURE_FLAG_3D_GYROGyroscope sensor failure.
32HL_FAILURE_FLAG_3D_MAGMagnetometer sensor failure.
64HL_FAILURE_FLAG_TERRAINTerrain subsystem failure.
128HL_FAILURE_FLAG_BATTERYBattery failure/critical low battery.
256HL_FAILURE_FLAG_RC_RECEIVERRC receiver failure/no rc connection.
1024HL_FAILURE_FLAG_ENGINEEngine failure.
2048HL_FAILURE_FLAG_GEOFENCEGeofence violation.
4096HL_FAILURE_FLAG_ESTIMATOREstimator failure, for example measurement rejection or large variances.
8192HL_FAILURE_FLAG_MISSIONMission failure.

MAV_MODE_FLAG

These flags encode the MAV mode.

ValueField NameDescription
128MAV_MODE_FLAG_SAFETY_ARMED0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state.
64MAV_MODE_FLAG_MANUAL_INPUT_ENABLED0b01000000 remote control input is enabled.
32MAV_MODE_FLAG_HIL_ENABLED0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
16MAV_MODE_FLAG_STABILIZE_ENABLED0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
8MAV_MODE_FLAG_GUIDED_ENABLED0b00001000 guided mode enabled, system flies waypoints / mission items.
4MAV_MODE_FLAG_AUTO_ENABLED0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
2MAV_MODE_FLAG_TEST_ENABLED0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
1MAV_MODE_FLAG_CUSTOM_MODE_ENABLED0b00000001 Reserved for future use.

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

ValueField NameDescription
128MAV_MODE_FLAG_DECODE_POSITION_SAFETYFirst bit: 10000000
64MAV_MODE_FLAG_DECODE_POSITION_MANUALSecond bit: 01000000
32MAV_MODE_FLAG_DECODE_POSITION_HILThird bit: 00100000
16MAV_MODE_FLAG_DECODE_POSITION_STABILIZEFourth bit: 00010000
8MAV_MODE_FLAG_DECODE_POSITION_GUIDEDFifth bit: 00001000
4MAV_MODE_FLAG_DECODE_POSITION_AUTOSixt bit: 00000100
2MAV_MODE_FLAG_DECODE_POSITION_TESTSeventh bit: 00000010
1MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODEEighth bit: 00000001

MAV_GOTO

Override command, pauses current mission execution and moves immediately to a position

ValueField NameDescription
0MAV_GOTO_DO_HOLDHold at the current position.
1MAV_GOTO_DO_CONTINUEContinue with the next item in mission execution.
2MAV_GOTO_HOLD_AT_CURRENT_POSITIONHold at the current position of the system
3MAV_GOTO_HOLD_AT_SPECIFIED_POSITIONHold at the position specified in the parameters of the DO_HOLD action

MAV_MODE

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.

ValueField NameDescription
0MAV_MODE_PREFLIGHTSystem is not ready to fly, booting, calibrating, etc. No flag is set.
80MAV_MODE_STABILIZE_DISARMEDSystem is allowed to be active, under assisted RC control.
208MAV_MODE_STABILIZE_ARMEDSystem is allowed to be active, under assisted RC control.
64MAV_MODE_MANUAL_DISARMEDSystem is allowed to be active, under manual (RC) control, no stabilization
192MAV_MODE_MANUAL_ARMEDSystem is allowed to be active, under manual (RC) control, no stabilization
88MAV_MODE_GUIDED_DISARMEDSystem is allowed to be active, under autonomous control, manual setpoint
216MAV_MODE_GUIDED_ARMEDSystem is allowed to be active, under autonomous control, manual setpoint
92MAV_MODE_AUTO_DISARMEDSystem is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
220MAV_MODE_AUTO_ARMEDSystem is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
66MAV_MODE_TEST_DISARMEDUNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
194MAV_MODE_TEST_ARMEDUNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.

MAV_STATE

ValueField NameDescription
0MAV_STATE_UNINITUninitialized system, state is unknown.
MAV_STATE_BOOTSystem is booting up.
MAV_STATE_CALIBRATINGSystem is calibrating and not flight-ready.
MAV_STATE_STANDBYSystem is grounded and on standby. It can be launched any time.
MAV_STATE_ACTIVESystem is active and might be already airborne. Motors are engaged.
MAV_STATE_CRITICALSystem is in a non-normal flight mode. It can however still navigate.
MAV_STATE_EMERGENCYSystem is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.
MAV_STATE_POWEROFFSystem just initialized its power-down sequence, will shut down now.
MAV_STATE_FLIGHT_TERMINATIONSystem is terminating itself.

MAV_COMPONENT

ValueField NameDescription
0MAV_COMP_ID_ALL
1MAV_COMP_ID_AUTOPILOT1
100MAV_COMP_ID_CAMERA
101MAV_COMP_ID_CAMERA2
102MAV_COMP_ID_CAMERA3
103MAV_COMP_ID_CAMERA4
104MAV_COMP_ID_CAMERA5
105MAV_COMP_ID_CAMERA6
140MAV_COMP_ID_SERVO1
141MAV_COMP_ID_SERVO2
142MAV_COMP_ID_SERVO3
143MAV_COMP_ID_SERVO4
144MAV_COMP_ID_SERVO5
145MAV_COMP_ID_SERVO6
146MAV_COMP_ID_SERVO7
147MAV_COMP_ID_SERVO8
148MAV_COMP_ID_SERVO9
149MAV_COMP_ID_SERVO10
150MAV_COMP_ID_SERVO11
151MAV_COMP_ID_SERVO12
152MAV_COMP_ID_SERVO13
153MAV_COMP_ID_SERVO14
154MAV_COMP_ID_GIMBAL
155MAV_COMP_ID_LOG
156MAV_COMP_ID_ADSB
157MAV_COMP_ID_OSDOn Screen Display (OSD) devices for video links
158MAV_COMP_ID_PERIPHERALGeneric autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol
159MAV_COMP_ID_QX1_GIMBAL
160MAV_COMP_ID_FLARM
180MAV_COMP_ID_MAPPER
190MAV_COMP_ID_MISSIONPLANNER
195MAV_COMP_ID_PATHPLANNER
196MAV_COMP_ID_OBSTACLE_AVOIDANCE
197MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY
200MAV_COMP_ID_IMU
201MAV_COMP_ID_IMU_2
202MAV_COMP_ID_IMU_3
220MAV_COMP_ID_GPS
221MAV_COMP_ID_GPS2
240MAV_COMP_ID_UDP_BRIDGE
241MAV_COMP_ID_UART_BRIDGE
250MAV_COMP_ID_SYSTEM_CONTROL

MAV_SYS_STATUS_SENSOR

These encode the sensors whose status is sent as part of the SYS_STATUS message.

ValueField NameDescription
1MAV_SYS_STATUS_SENSOR_3D_GYRO0x01 3D gyro
2MAV_SYS_STATUS_SENSOR_3D_ACCEL0x02 3D accelerometer
4MAV_SYS_STATUS_SENSOR_3D_MAG0x04 3D magnetometer
8MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE0x08 absolute pressure
16MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE0x10 differential pressure
32MAV_SYS_STATUS_SENSOR_GPS0x20 GPS
64MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW0x40 optical flow
128MAV_SYS_STATUS_SENSOR_VISION_POSITION0x80 computer vision position
256MAV_SYS_STATUS_SENSOR_LASER_POSITION0x100 laser based position
512MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH0x200 external ground truth (Vicon or Leica)
1024MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL0x400 3D angular rate control
2048MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION0x800 attitude stabilization
4096MAV_SYS_STATUS_SENSOR_YAW_POSITION0x1000 yaw position
8192MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL0x2000 z/altitude control
16384MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL0x4000 x/y position control
32768MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS0x8000 motor outputs / control
65536MAV_SYS_STATUS_SENSOR_RC_RECEIVER0x10000 rc receiver
131072MAV_SYS_STATUS_SENSOR_3D_GYRO20x20000 2nd 3D gyro
262144MAV_SYS_STATUS_SENSOR_3D_ACCEL20x40000 2nd 3D accelerometer
524288MAV_SYS_STATUS_SENSOR_3D_MAG20x80000 2nd 3D magnetometer
1048576MAV_SYS_STATUS_GEOFENCE0x100000 geofence
2097152MAV_SYS_STATUS_AHRS0x200000 AHRS subsystem health
4194304MAV_SYS_STATUS_TERRAIN0x400000 Terrain subsystem health
8388608MAV_SYS_STATUS_REVERSE_MOTOR0x800000 Motors are reversed
16777216MAV_SYS_STATUS_LOGGING0x1000000 Logging
33554432MAV_SYS_STATUS_SENSOR_BATTERY0x2000000 Battery
67108864MAV_SYS_STATUS_SENSOR_PROXIMITY0x4000000 Proximity
134217728MAV_SYS_STATUS_SENSOR_SATCOM0x8000000 Satellite Communication

MAV_FRAME

ValueField NameDescription
0MAV_FRAME_GLOBALGlobal coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
1MAV_FRAME_LOCAL_NEDLocal coordinate frame, Z-down (x: north, y: east, z: down).
2MAV_FRAME_MISSIONNOT a coordinate frame, indicates a mission command.
3MAV_FRAME_GLOBAL_RELATIVE_ALTGlobal coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
4MAV_FRAME_LOCAL_ENULocal coordinate frame, Z-up (x: east, y: north, z: up).
5MAV_FRAME_GLOBAL_INTGlobal coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL).
6MAV_FRAME_GLOBAL_RELATIVE_ALT_INTGlobal coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.
7MAV_FRAME_LOCAL_OFFSET_NEDOffset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
8MAV_FRAME_BODY_NEDSetpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.
9MAV_FRAME_BODY_OFFSET_NEDOffset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.
10MAV_FRAME_GLOBAL_TERRAIN_ALTGlobal (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
11MAV_FRAME_GLOBAL_TERRAIN_ALT_INTGlobal (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
12MAV_FRAME_BODY_FRDBody fixed frame of reference, Z-down (x: forward, y: right, z: down).
13MAV_FRAME_BODY_FLUBody fixed frame of reference, Z-up (x: forward, y: left, z: up).
14MAV_FRAME_MOCAP_NEDOdometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down).
15MAV_FRAME_MOCAP_ENUOdometry local coordinate frame of data given by a motion capture system, Z-up (x: east, y: north, z: up).
16MAV_FRAME_VISION_NEDOdometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down).
17MAV_FRAME_VISION_ENUOdometry local coordinate frame of data given by a vision estimation system, Z-up (x: east, y: north, z: up).
18MAV_FRAME_ESTIM_NEDOdometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down).
19MAV_FRAME_ESTIM_ENUOdometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: east, y: noth, z: up).

ValueField NameDescription

FENCE_ACTION

ValueField NameDescription
0FENCE_ACTION_NONEDisable fenced mode
1FENCE_ACTION_GUIDEDSwitched to guided mode to return point (fence point 0)
2FENCE_ACTION_REPORTReport fence breach, but don't take action
3FENCE_ACTION_GUIDED_THR_PASSSwitched to guided mode to return point (fence point 0) with manual throttle control
4FENCE_ACTION_RTLSwitch to RTL (return to launch) mode and head for the return point.

FENCE_BREACH

ValueField NameDescription
0FENCE_BREACH_NONENo last fence breach
1FENCE_BREACH_MINALTBreached minimum altitude
2FENCE_BREACH_MAXALTBreached maximum altitude
3FENCE_BREACH_BOUNDARYBreached fence boundary

MAV_MOUNT_MODE

Enumeration of possible mount operation modes

ValueField NameDescription
0MAV_MOUNT_MODE_RETRACTLoad and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization
1MAV_MOUNT_MODE_NEUTRALLoad and keep neutral position (Roll,Pitch,Yaw) from permanent memory.
3MAV_MOUNT_MODE_RC_TARGETINGLoad neutral position and start RC Roll,Pitch,Yaw control with stabilization
4MAV_MOUNT_MODE_GPS_POINTLoad neutral position and start to point to Lat,Lon,Alt

UAVCAN_NODE_HEALTH

Generalized UAVCAN node health

ValueField NameDescription
0UAVCAN_NODE_HEALTH_OKThe node is functioning properly.
1UAVCAN_NODE_HEALTH_WARNINGA critical parameter went out of range or the node has encountered a minor failure.
2UAVCAN_NODE_HEALTH_ERRORThe node has encountered a major failure.
3UAVCAN_NODE_HEALTH_CRITICALThe node has suffered a fatal malfunction.

UAVCAN_NODE_MODE

Generalized UAVCAN node mode

ValueField NameDescription
0UAVCAN_NODE_MODE_OPERATIONALThe node is performing its primary functions.
1UAVCAN_NODE_MODE_INITIALIZATIONThe node is initializing; this mode is entered immediately after startup.
2UAVCAN_NODE_MODE_MAINTENANCEThe node is under maintenance.
3UAVCAN_NODE_MODE_SOFTWARE_UPDATEThe node is in the process of updating its software.
7UAVCAN_NODE_MODE_OFFLINEThe node is no longer available online.

MAV_DATA_STREAM

DEPRECATED: Replaced by MESSAGE_INTERVAL (2015-06).

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.

ValueField NameDescription
0MAV_DATA_STREAM_ALLEnable all data streams
1MAV_DATA_STREAM_RAW_SENSORSEnable IMU_RAW, GPS_RAW, GPS_STATUS packets.
2MAV_DATA_STREAM_EXTENDED_STATUSEnable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
3MAV_DATA_STREAM_RC_CHANNELSEnable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
4MAV_DATA_STREAM_RAW_CONTROLLEREnable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
6MAV_DATA_STREAM_POSITIONEnable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
10MAV_DATA_STREAM_EXTRA1Dependent on the autopilot
11MAV_DATA_STREAM_EXTRA2Dependent on the autopilot
12MAV_DATA_STREAM_EXTRA3Dependent on the autopilot

MAV_ROI

DEPRECATED: Replaced by MAV_CMD_DO_SET_ROI_* (2018-01).

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

ValueField NameDescription
0MAV_ROI_NONENo region of interest.
1MAV_ROI_WPNEXTPoint toward next waypoint, with optional pitch/roll/yaw offset.
2MAV_ROI_WPINDEXPoint toward given waypoint.
3MAV_ROI_LOCATIONPoint toward fixed location.
4MAV_ROI_TARGETPoint toward of given id.

MAV_CMD_ACK

ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.

ValueField NameDescription
MAV_CMD_ACK_OKCommand / mission item is ok.
MAV_CMD_ACK_ERR_FAILGeneric error message if none of the other reasons fails or if no detailed error reporting is implemented.
MAV_CMD_ACK_ERR_ACCESS_DENIEDThe system is refusing to accept this command from this source / communication partner.
MAV_CMD_ACK_ERR_NOT_SUPPORTEDCommand or mission item is not supported, other commands would be accepted.
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTEDThe coordinate frame of this command / mission item is not supported.
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGEThe coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGEThe X or latitude value is out of range.
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGEThe Y or longitude value is out of range.
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGEThe Z or altitude value is out of range.

MAV_PARAM_TYPE

Specifies the datatype of a MAVLink parameter.

ValueField NameDescription
1MAV_PARAM_TYPE_UINT88-bit unsigned integer
2MAV_PARAM_TYPE_INT88-bit signed integer
3MAV_PARAM_TYPE_UINT1616-bit unsigned integer
4MAV_PARAM_TYPE_INT1616-bit signed integer
5MAV_PARAM_TYPE_UINT3232-bit unsigned integer
6MAV_PARAM_TYPE_INT3232-bit signed integer
7MAV_PARAM_TYPE_UINT6464-bit unsigned integer
8MAV_PARAM_TYPE_INT6464-bit signed integer
9MAV_PARAM_TYPE_REAL3232-bit floating-point
10MAV_PARAM_TYPE_REAL6464-bit floating-point

MAV_PARAM_EXT_TYPE

Specifies the datatype of a MAVLink extended parameter.

ValueField NameDescription
1MAV_PARAM_EXT_TYPE_UINT88-bit unsigned integer
2MAV_PARAM_EXT_TYPE_INT88-bit signed integer
3MAV_PARAM_EXT_TYPE_UINT1616-bit unsigned integer
4MAV_PARAM_EXT_TYPE_INT1616-bit signed integer
5MAV_PARAM_EXT_TYPE_UINT3232-bit unsigned integer
6MAV_PARAM_EXT_TYPE_INT3232-bit signed integer
7MAV_PARAM_EXT_TYPE_UINT6464-bit unsigned integer
8MAV_PARAM_EXT_TYPE_INT6464-bit signed integer
9MAV_PARAM_EXT_TYPE_REAL3232-bit floating-point
10MAV_PARAM_EXT_TYPE_REAL6464-bit floating-point
11MAV_PARAM_EXT_TYPE_CUSTOMCustom Type

MAV_RESULT

result from a mavlink command

ValueField NameDescription
0MAV_RESULT_ACCEPTEDCommand ACCEPTED and EXECUTED
1MAV_RESULT_TEMPORARILY_REJECTEDCommand TEMPORARY REJECTED/DENIED
2MAV_RESULT_DENIEDCommand PERMANENTLY DENIED
3MAV_RESULT_UNSUPPORTEDCommand UNKNOWN/UNSUPPORTED
4MAV_RESULT_FAILEDCommand executed, but failed
5MAV_RESULT_IN_PROGRESSWIP: Command being executed

MAV_MISSION_RESULT

result in a MAVLink mission ack

ValueField NameDescription
0MAV_MISSION_ACCEPTEDmission accepted OK
1MAV_MISSION_ERRORgeneric error / not accepting mission commands at all right now
2MAV_MISSION_UNSUPPORTED_FRAMEcoordinate frame is not supported
3MAV_MISSION_UNSUPPORTEDcommand is not supported
4MAV_MISSION_NO_SPACEmission item exceeds storage space
5MAV_MISSION_INVALIDone of the parameters has an invalid value
6MAV_MISSION_INVALID_PARAM1param1 has an invalid value
7MAV_MISSION_INVALID_PARAM2param2 has an invalid value
8MAV_MISSION_INVALID_PARAM3param3 has an invalid value
9MAV_MISSION_INVALID_PARAM4param4 has an invalid value
10MAV_MISSION_INVALID_PARAM5_Xx/param5 has an invalid value
11MAV_MISSION_INVALID_PARAM6_Yy/param6 has an invalid value
12MAV_MISSION_INVALID_PARAM7param7 has an invalid value
13MAV_MISSION_INVALID_SEQUENCEreceived waypoint out of sequence
14MAV_MISSION_DENIEDnot accepting any mission commands from this communication partner

MAV_SEVERITY

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

ValueField NameDescription
0MAV_SEVERITY_EMERGENCYSystem is unusable. This is a "panic" condition.
1MAV_SEVERITY_ALERTAction should be taken immediately. Indicates error in non-critical systems.
2MAV_SEVERITY_CRITICALAction must be taken immediately. Indicates failure in a primary system.
3MAV_SEVERITY_ERRORIndicates an error in secondary/redundant systems.
4MAV_SEVERITY_WARNINGIndicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.
5MAV_SEVERITY_NOTICEAn unusual event has occurred, though not an error condition. This should be investigated for the root cause.
6MAV_SEVERITY_INFONormal operational messages. Useful for logging. No action is required for these messages.
7MAV_SEVERITY_DEBUGUseful non-operational messages that can assist in debugging. These should not occur during normal operation.

MAV_POWER_STATUS

Power supply status flags (bitmask)

ValueField NameDescription
1MAV_POWER_STATUS_BRICK_VALIDmain brick power supply valid
2MAV_POWER_STATUS_SERVO_VALIDmain servo power supply valid for FMU
4MAV_POWER_STATUS_USB_CONNECTEDUSB power is connected
8MAV_POWER_STATUS_PERIPH_OVERCURRENTperipheral supply is in over-current state
16MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENThi-power peripheral supply is in over-current state
32MAV_POWER_STATUS_CHANGEDPower status has changed since boot

SERIAL_CONTROL_DEV

SERIAL_CONTROL device types

ValueField NameDescription
0SERIAL_CONTROL_DEV_TELEM1First telemetry port
1SERIAL_CONTROL_DEV_TELEM2Second telemetry port
2SERIAL_CONTROL_DEV_GPS1First GPS port
3SERIAL_CONTROL_DEV_GPS2Second GPS port
10SERIAL_CONTROL_DEV_SHELLsystem shell

SERIAL_CONTROL_FLAG

SERIAL_CONTROL flags (bitmask)

ValueField NameDescription
1SERIAL_CONTROL_FLAG_REPLYSet if this is a reply
2SERIAL_CONTROL_FLAG_RESPONDSet if the sender wants the receiver to send a response as another SERIAL_CONTROL message
4SERIAL_CONTROL_FLAG_EXCLUSIVESet if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set
8SERIAL_CONTROL_FLAG_BLOCKINGBlock on writes to the serial port
16SERIAL_CONTROL_FLAG_MULTISend multiple replies until port is drained

MAV_DISTANCE_SENSOR

Enumeration of distance sensor types

ValueField NameDescription
0MAV_DISTANCE_SENSOR_LASERLaser rangefinder, e.g. LightWare SF02/F or PulsedLight units
1MAV_DISTANCE_SENSOR_ULTRASOUNDUltrasound rangefinder, e.g. MaxBotix units
2MAV_DISTANCE_SENSOR_INFRAREDInfrared rangefinder, e.g. Sharp units
3MAV_DISTANCE_SENSOR_RADARRadar type, e.g. uLanding units
4MAV_DISTANCE_SENSOR_UNKNOWNBroken or unknown type, e.g. analog units

MAV_SENSOR_ORIENTATION

Enumeration of sensor orientation, according to its rotations

ValueField NameDescription
0MAV_SENSOR_ROTATION_NONERoll: 0, Pitch: 0, Yaw: 0
1MAV_SENSOR_ROTATION_YAW_45Roll: 0, Pitch: 0, Yaw: 45
2MAV_SENSOR_ROTATION_YAW_90Roll: 0, Pitch: 0, Yaw: 90
3MAV_SENSOR_ROTATION_YAW_135Roll: 0, Pitch: 0, Yaw: 135
4MAV_SENSOR_ROTATION_YAW_180Roll: 0, Pitch: 0, Yaw: 180
5MAV_SENSOR_ROTATION_YAW_225Roll: 0, Pitch: 0, Yaw: 225
6MAV_SENSOR_ROTATION_YAW_270Roll: 0, Pitch: 0, Yaw: 270
7MAV_SENSOR_ROTATION_YAW_315Roll: 0, Pitch: 0, Yaw: 315
8MAV_SENSOR_ROTATION_ROLL_180Roll: 180, Pitch: 0, Yaw: 0
9MAV_SENSOR_ROTATION_ROLL_180_YAW_45Roll: 180, Pitch: 0, Yaw: 45
10MAV_SENSOR_ROTATION_ROLL_180_YAW_90Roll: 180, Pitch: 0, Yaw: 90
11MAV_SENSOR_ROTATION_ROLL_180_YAW_135Roll: 180, Pitch: 0, Yaw: 135
12MAV_SENSOR_ROTATION_PITCH_180Roll: 0, Pitch: 180, Yaw: 0
13MAV_SENSOR_ROTATION_ROLL_180_YAW_225Roll: 180, Pitch: 0, Yaw: 225
14MAV_SENSOR_ROTATION_ROLL_180_YAW_270Roll: 180, Pitch: 0, Yaw: 270
15MAV_SENSOR_ROTATION_ROLL_180_YAW_315Roll: 180, Pitch: 0, Yaw: 315
16MAV_SENSOR_ROTATION_ROLL_90Roll: 90, Pitch: 0, Yaw: 0
17MAV_SENSOR_ROTATION_ROLL_90_YAW_45Roll: 90, Pitch: 0, Yaw: 45
18MAV_SENSOR_ROTATION_ROLL_90_YAW_90Roll: 90, Pitch: 0, Yaw: 90
19MAV_SENSOR_ROTATION_ROLL_90_YAW_135Roll: 90, Pitch: 0, Yaw: 135
20MAV_SENSOR_ROTATION_ROLL_270Roll: 270, Pitch: 0, Yaw: 0
21MAV_SENSOR_ROTATION_ROLL_270_YAW_45Roll: 270, Pitch: 0, Yaw: 45
22MAV_SENSOR_ROTATION_ROLL_270_YAW_90Roll: 270, Pitch: 0, Yaw: 90
23MAV_SENSOR_ROTATION_ROLL_270_YAW_135Roll: 270, Pitch: 0, Yaw: 135
24MAV_SENSOR_ROTATION_PITCH_90Roll: 0, Pitch: 90, Yaw: 0
25MAV_SENSOR_ROTATION_PITCH_270Roll: 0, Pitch: 270, Yaw: 0
26MAV_SENSOR_ROTATION_PITCH_180_YAW_90Roll: 0, Pitch: 180, Yaw: 90
27MAV_SENSOR_ROTATION_PITCH_180_YAW_270Roll: 0, Pitch: 180, Yaw: 270
28MAV_SENSOR_ROTATION_ROLL_90_PITCH_90Roll: 90, Pitch: 90, Yaw: 0
29MAV_SENSOR_ROTATION_ROLL_180_PITCH_90Roll: 180, Pitch: 90, Yaw: 0
30MAV_SENSOR_ROTATION_ROLL_270_PITCH_90Roll: 270, Pitch: 90, Yaw: 0
31MAV_SENSOR_ROTATION_ROLL_90_PITCH_180Roll: 90, Pitch: 180, Yaw: 0
32MAV_SENSOR_ROTATION_ROLL_270_PITCH_180Roll: 270, Pitch: 180, Yaw: 0
33MAV_SENSOR_ROTATION_ROLL_90_PITCH_270Roll: 90, Pitch: 270, Yaw: 0
34MAV_SENSOR_ROTATION_ROLL_180_PITCH_270Roll: 180, Pitch: 270, Yaw: 0
35MAV_SENSOR_ROTATION_ROLL_270_PITCH_270Roll: 270, Pitch: 270, Yaw: 0
36MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90Roll: 90, Pitch: 180, Yaw: 90
37MAV_SENSOR_ROTATION_ROLL_90_YAW_270Roll: 90, Pitch: 0, Yaw: 270
38MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293Roll: 90, Pitch: 68, Yaw: 293
39MAV_SENSOR_ROTATION_PITCH_315Pitch: 315
40MAV_SENSOR_ROTATION_ROLL_90_PITCH_315Roll: 90, Pitch: 315
100MAV_SENSOR_ROTATION_CUSTOMCustom orientation

MAV_PROTOCOL_CAPABILITY

Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.

ValueField NameDescription
1MAV_PROTOCOL_CAPABILITY_MISSION_FLOATAutopilot supports MISSION float message type.
2MAV_PROTOCOL_CAPABILITY_PARAM_FLOATAutopilot supports the new param float message type.
4MAV_PROTOCOL_CAPABILITY_MISSION_INTAutopilot supports MISSION_INT scaled integer message type.
8MAV_PROTOCOL_CAPABILITY_COMMAND_INTAutopilot supports COMMAND_INT scaled integer message type.
16MAV_PROTOCOL_CAPABILITY_PARAM_UNIONAutopilot supports the new param union message type.
32MAV_PROTOCOL_CAPABILITY_FTPAutopilot supports the new FILE_TRANSFER_PROTOCOL message type.
64MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGETAutopilot supports commanding attitude offboard.
128MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NEDAutopilot supports commanding position and velocity targets in local NED frame.
256MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INTAutopilot supports commanding position and velocity targets in global scaled integers.
512MAV_PROTOCOL_CAPABILITY_TERRAINAutopilot supports terrain protocol / data handling.
1024MAV_PROTOCOL_CAPABILITY_SET_ACTUATOR_TARGETAutopilot supports direct actuator control.
2048MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATIONAutopilot supports the flight termination command.
4096MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATIONAutopilot supports onboard compass calibration.
8192MAV_PROTOCOL_CAPABILITY_MAVLINK2Autopilot supports MAVLink version 2.
16384MAV_PROTOCOL_CAPABILITY_MISSION_FENCEAutopilot supports mission fence protocol.
32768MAV_PROTOCOL_CAPABILITY_MISSION_RALLYAutopilot supports mission rally point protocol.
65536MAV_PROTOCOL_CAPABILITY_FLIGHT_INFORMATIONAutopilot supports the flight information protocol.

MAV_MISSION_TYPE

Type of mission items being requested/sent in mission protocol.

ValueField NameDescription
0MAV_MISSION_TYPE_MISSIONItems are mission commands for main mission.
1MAV_MISSION_TYPE_FENCESpecifies GeoFence area(s). Items are MAV_CMD_FENCE_ GeoFence items.
2MAV_MISSION_TYPE_RALLYSpecifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_RALLY_POINT rally point items.
255MAV_MISSION_TYPE_ALLOnly used in MISSION_CLEAR_ALL to clear all mission types.

MAV_ESTIMATOR_TYPE

Enumeration of estimator types

ValueField NameDescription
1MAV_ESTIMATOR_TYPE_NAIVEThis is a naive estimator without any real covariance feedback.
2MAV_ESTIMATOR_TYPE_VISIONComputer vision based estimate. Might be up to scale.
3MAV_ESTIMATOR_TYPE_VIOVisual-inertial estimate.
4MAV_ESTIMATOR_TYPE_GPSPlain GPS estimate.
5MAV_ESTIMATOR_TYPE_GPS_INSEstimator integrating GPS and inertial sensing.

MAV_BATTERY_TYPE

Enumeration of battery types

ValueField NameDescription
0MAV_BATTERY_TYPE_UNKNOWNNot specified.
1MAV_BATTERY_TYPE_LIPOLithium polymer battery
2MAV_BATTERY_TYPE_LIFELithium-iron-phosphate battery
3MAV_BATTERY_TYPE_LIONLithium-ION battery
4MAV_BATTERY_TYPE_NIMHNickel metal hydride battery

MAV_BATTERY_FUNCTION

Enumeration of battery functions

ValueField NameDescription
0MAV_BATTERY_FUNCTION_UNKNOWNBattery function is unknown
1MAV_BATTERY_FUNCTION_ALLBattery supports all flight systems
2MAV_BATTERY_FUNCTION_PROPULSIONBattery for the propulsion system
3MAV_BATTERY_FUNCTION_AVIONICSAvionics battery
4MAV_BATTERY_TYPE_PAYLOADPayload battery

MAV_BATTERY_CHARGE_STATE

Enumeration for low battery states.

ValueField NameDescription
0MAV_BATTERY_CHARGE_STATE_UNDEFINEDLow battery state is not provided
1MAV_BATTERY_CHARGE_STATE_OKBattery is not in low state. Normal operation.
2MAV_BATTERY_CHARGE_STATE_LOWBattery state is low, warn and monitor close.
3MAV_BATTERY_CHARGE_STATE_CRITICALBattery state is critical, return or abort immediately.
4MAV_BATTERY_CHARGE_STATE_EMERGENCYBattery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage.
5MAV_BATTERY_CHARGE_STATE_FAILEDBattery failed, damage unavoidable.
6MAV_BATTERY_CHARGE_STATE_UNHEALTHYBattery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited.

MAV_VTOL_STATE

Enumeration of VTOL states

ValueField NameDescription
0MAV_VTOL_STATE_UNDEFINEDMAV is not configured as VTOL
1MAV_VTOL_STATE_TRANSITION_TO_FWVTOL is in transition from multicopter to fixed-wing
2MAV_VTOL_STATE_TRANSITION_TO_MCVTOL is in transition from fixed-wing to multicopter
3MAV_VTOL_STATE_MCVTOL is in multicopter state
4MAV_VTOL_STATE_FWVTOL is in fixed-wing state

MAV_LANDED_STATE

Enumeration of landed detector states

ValueField NameDescription
0MAV_LANDED_STATE_UNDEFINEDMAV landed state is unknown
1MAV_LANDED_STATE_ON_GROUNDMAV is landed (on ground)
2MAV_LANDED_STATE_IN_AIRMAV is in air
3MAV_LANDED_STATE_TAKEOFFMAV currently taking off
4MAV_LANDED_STATE_LANDINGMAV currently landing

ADSB_ALTITUDE_TYPE

Enumeration of the ADSB altimeter types

ValueField NameDescription
0ADSB_ALTITUDE_TYPE_PRESSURE_QNHAltitude reported from a Baro source using QNH reference
1ADSB_ALTITUDE_TYPE_GEOMETRICAltitude reported from a GNSS source

ADSB_EMITTER_TYPE

ADSB classification for the type of vehicle emitting the transponder signal

ValueField NameDescription
0ADSB_EMITTER_TYPE_NO_INFO
1ADSB_EMITTER_TYPE_LIGHT
2ADSB_EMITTER_TYPE_SMALL
3ADSB_EMITTER_TYPE_LARGE
4ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE
5ADSB_EMITTER_TYPE_HEAVY
6ADSB_EMITTER_TYPE_HIGHLY_MANUV
7ADSB_EMITTER_TYPE_ROTOCRAFT
8ADSB_EMITTER_TYPE_UNASSIGNED
9ADSB_EMITTER_TYPE_GLIDER
10ADSB_EMITTER_TYPE_LIGHTER_AIR
11ADSB_EMITTER_TYPE_PARACHUTE
12ADSB_EMITTER_TYPE_ULTRA_LIGHT
13ADSB_EMITTER_TYPE_UNASSIGNED2
14ADSB_EMITTER_TYPE_UAV
15ADSB_EMITTER_TYPE_SPACE
16ADSB_EMITTER_TYPE_UNASSGINED3
17ADSB_EMITTER_TYPE_EMERGENCY_SURFACE
18ADSB_EMITTER_TYPE_SERVICE_SURFACE
19ADSB_EMITTER_TYPE_POINT_OBSTACLE

ADSB_FLAGS

These flags indicate status such as data validity of each data source. Set = data valid

ValueField NameDescription
1ADSB_FLAGS_VALID_COORDS
2ADSB_FLAGS_VALID_ALTITUDE
4ADSB_FLAGS_VALID_HEADING
8ADSB_FLAGS_VALID_VELOCITY
16ADSB_FLAGS_VALID_CALLSIGN
32ADSB_FLAGS_VALID_SQUAWK
64ADSB_FLAGS_SIMULATED

MAV_DO_REPOSITION_FLAGS

Bitmap of options for the MAV_CMD_DO_REPOSITION

ValueField NameDescription
1MAV_DO_REPOSITION_FLAGS_CHANGE_MODEThe aircraft should immediately transition into guided. This should not be set for follow me applications

ESTIMATOR_STATUS_FLAGS

Flags in EKF_STATUS message

ValueField NameDescription
1ESTIMATOR_ATTITUDETrue if the attitude estimate is good
2ESTIMATOR_VELOCITY_HORIZTrue if the horizontal velocity estimate is good
4ESTIMATOR_VELOCITY_VERTTrue if the vertical velocity estimate is good
8ESTIMATOR_POS_HORIZ_RELTrue if the horizontal position (relative) estimate is good
16ESTIMATOR_POS_HORIZ_ABSTrue if the horizontal position (absolute) estimate is good
32ESTIMATOR_POS_VERT_ABSTrue if the vertical position (absolute) estimate is good
64ESTIMATOR_POS_VERT_AGLTrue if the vertical position (above ground) estimate is good
128ESTIMATOR_CONST_POS_MODETrue if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
256ESTIMATOR_PRED_POS_HORIZ_RELTrue if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
512ESTIMATOR_PRED_POS_HORIZ_ABSTrue if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
1024ESTIMATOR_GPS_GLITCHTrue if the EKF has detected a GPS glitch
2048ESTIMATOR_ACCEL_ERRORTrue if the EKF has detected bad accelerometer data

MOTOR_TEST_ORDER

ValueField NameDescription
0MOTOR_TEST_ORDER_DEFAULTdefault autopilot motor test method
1MOTOR_TEST_ORDER_SEQUENCEmotor numbers are specified as their index in a predefined vehicle-specific sequence
2MOTOR_TEST_ORDER_BOARDmotor numbers are specified as the output as labeled on the board

MOTOR_TEST_THROTTLE_TYPE

ValueField NameDescription
0MOTOR_TEST_THROTTLE_PERCENTthrottle as a percentage from 0 ~ 100
1MOTOR_TEST_THROTTLE_PWMthrottle as an absolute PWM value (normally in range of 1000~2000)
2MOTOR_TEST_THROTTLE_PILOTthrottle pass-through from pilot's transmitter
3MOTOR_TEST_COMPASS_CALper-motor compass calibration test

GPS_INPUT_IGNORE_FLAGS

ValueField NameDescription
1GPS_INPUT_IGNORE_FLAG_ALTignore altitude field
2GPS_INPUT_IGNORE_FLAG_HDOPignore hdop field
4GPS_INPUT_IGNORE_FLAG_VDOPignore vdop field
8GPS_INPUT_IGNORE_FLAG_VEL_HORIZignore horizontal velocity field (vn and ve)
16GPS_INPUT_IGNORE_FLAG_VEL_VERTignore vertical velocity field (vd)
32GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACYignore speed accuracy field
64GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACYignore horizontal accuracy field
128GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACYignore vertical accuracy field

MAV_COLLISION_ACTION

Possible actions an aircraft can take to avoid a collision.

ValueField NameDescription
0MAV_COLLISION_ACTION_NONEIgnore any potential collisions
1MAV_COLLISION_ACTION_REPORTReport potential collision
2MAV_COLLISION_ACTION_ASCEND_OR_DESCENDAscend or Descend to avoid threat
3MAV_COLLISION_ACTION_MOVE_HORIZONTALLYMove horizontally to avoid threat
4MAV_COLLISION_ACTION_MOVE_PERPENDICULARAircraft to move perpendicular to the collision's velocity vector
5MAV_COLLISION_ACTION_RTLAircraft to fly directly back to its launch point
6MAV_COLLISION_ACTION_HOVERAircraft to stop in place

MAV_COLLISION_THREAT_LEVEL

Aircraft-rated danger from this threat.

ValueField NameDescription
0MAV_COLLISION_THREAT_LEVEL_NONENot a threat
1MAV_COLLISION_THREAT_LEVEL_LOWCraft is mildly concerned about this threat
2MAV_COLLISION_THREAT_LEVEL_HIGHCraft is panicing, and may take actions to avoid threat

MAV_COLLISION_SRC

Source of information about this collision.

ValueField NameDescription
0MAV_COLLISION_SRC_ADSBID field references ADSB_VEHICLE packets

GPS_FIX_TYPE

Type of GPS fix

ValueField NameDescription
0GPS_FIX_TYPE_NO_GPSNo GPS connected
1GPS_FIX_TYPE_NO_FIXNo position information, GPS is connected
2GPS_FIX_TYPE_2D_FIX2D position
3GPS_FIX_TYPE_3D_FIX3D position
4GPS_FIX_TYPE_DGPSDGPS/SBAS aided 3D position
5GPS_FIX_TYPE_RTK_FLOATRTK float, 3D position
6GPS_FIX_TYPE_RTK_FIXEDRTK Fixed, 3D position
7GPS_FIX_TYPE_STATICStatic fixed, typically used for base stations
8GPS_FIX_TYPE_PPPPPP, 3D position.

RTK_BASELINE_COORDINATE_SYSTEM

RTK GPS baseline coordinate system, used for RTK corrections

ValueField NameDescription
0RTK_BASELINE_COORDINATE_SYSTEM_ECEFEarth-centered, Earth-fixed
1RTK_BASELINE_COORDINATE_SYSTEM_NEDNorth, East, Down

LANDING_TARGET_TYPE

Type of landing target

ValueField NameDescription
0LANDING_TARGET_TYPE_LIGHT_BEACONLanding target signaled by light beacon (ex: IR-LOCK)
1LANDING_TARGET_TYPE_RADIO_BEACONLanding target signaled by radio beacon (ex: ILS, NDB)
2LANDING_TARGET_TYPE_VISION_FIDUCIALLanding target represented by a fiducial marker (ex: ARTag)
3LANDING_TARGET_TYPE_VISION_OTHERLanding target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)

VTOL_TRANSITION_HEADING

Direction of VTOL transition

ValueField NameDescription
0VTOL_TRANSITION_HEADING_VEHICLE_DEFAULTRespect the heading configuration of the vehicle.
1VTOL_TRANSITION_HEADING_NEXT_WAYPOINTUse the heading pointing towards the next waypoint.
2VTOL_TRANSITION_HEADING_TAKEOFFUse the heading on takeoff (while sitting on the ground).
3VTOL_TRANSITION_HEADING_SPECIFIEDUse the specified heading in parameter 4.
4VTOL_TRANSITION_HEADING_ANYUse the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active).

CAMERA_CAP_FLAGS

Camera capability flags (Bitmap)

ValueField NameDescription
1CAMERA_CAP_FLAGS_CAPTURE_VIDEOCamera is able to record video
2CAMERA_CAP_FLAGS_CAPTURE_IMAGECamera is able to capture images
4CAMERA_CAP_FLAGS_HAS_MODESCamera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)
8CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODECamera can capture images while in video mode
16CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODECamera can capture videos while in Photo/Image mode
32CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODECamera has image survey mode (MAV_CMD_SET_CAMERA_MODE)
64CAMERA_CAP_FLAGS_HAS_BASIC_ZOOMCamera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)
128CAMERA_CAP_FLAGS_HAS_BASIC_FOCUSCamera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)

VIDEO_STREAM_STATUS_FLAGS

Stream status flags (Bitmap)

ValueField NameDescription
1VIDEO_STREAM_STATUS_FLAGS_RUNNINGStream is active (running)
2VIDEO_STREAM_STATUS_FLAGS_THERMALStream is thermal imaging

SET_ZOOM_TYPE

Zoom types for MAV_CMD_SET_CAMERA_ZOOM

ValueField NameDescription
0ZOOM_TYPE_STEPZoom one step increment (-1 for wide, 1 for tele)
1ZOOM_TYPE_CONTINUOUSContinuous zoom up/down until stopped (-1 for wide, 1 for tele, 0 to stop zooming)
2ZOOM_TYPE_RANGEZoom value as proportion of full camera range (a value between 0.0 and 100.0)

SET_FOCUS_TYPE

Focus types for MAV_CMD_SET_CAMERA_FOCUS

ValueField NameDescription
0FOCUS_TYPE_STEPFocus one step increment (-1 for focusing in, 1 for focusing out towards infinity).
1FOCUS_TYPE_CONTINUOUSContinuous focus up/down until stopped (-1 for focusing in, 1 for focusing out towards infinity, 0 to stop focusing)
2FOCUS_TYPE_RANGEZoom value as proportion of full camera range (a value between 0.0 and 100.0)

PARAM_ACK

Result from a PARAM_EXT_SET message.

ValueField NameDescription
0PARAM_ACK_ACCEPTEDParameter value ACCEPTED and SET
1PARAM_ACK_VALUE_UNSUPPORTEDParameter value UNKNOWN/UNSUPPORTED
2PARAM_ACK_FAILEDParameter failed to set
3PARAM_ACK_IN_PROGRESSParameter value received but not yet validated or set. A subsequent PARAM_EXT_ACK will follow once operation is completed with the actual result. These are for parameters that may take longer to set. Instead of waiting for an ACK and potentially timing out, you will immediately receive this response to let you know it was received.

CAMERA_MODE

Camera Modes.

ValueField NameDescription
0CAMERA_MODE_IMAGECamera is in image/photo capture mode.
1CAMERA_MODE_VIDEOCamera is in video capture mode.
2CAMERA_MODE_IMAGE_SURVEYCamera is in image survey capture mode. It allows for camera controller to do specific settings for surveys.

MAV_ARM_AUTH_DENIED_REASON

ValueField NameDescription
0MAV_ARM_AUTH_DENIED_REASON_GENERICNot a specific reason
1MAV_ARM_AUTH_DENIED_REASON_NONEAuthorizer will send the error as string to GCS
2MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINTAt least one waypoint have a invalid value
3MAV_ARM_AUTH_DENIED_REASON_TIMEOUTTimeout in the authorizer process(in case it depends on network)
4MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USEAirspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied.
5MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHERWeather is not good to fly

RC_TYPE

RC type

ValueField NameDescription
0RC_TYPE_SPEKTRUM_DSM2Spektrum DSM2
1RC_TYPE_SPEKTRUM_DSMXSpektrum DSMX

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.

ValueField NameDescription
1POSITION_TARGET_TYPEMASK_X_IGNOREIgnore position x
2POSITION_TARGET_TYPEMASK_Y_IGNOREIgnore position y
4POSITION_TARGET_TYPEMASK_Z_IGNOREIgnore position z
8POSITION_TARGET_TYPEMASK_VX_IGNOREIgnore velocity x
16POSITION_TARGET_TYPEMASK_VY_IGNOREIgnore velocity y
32POSITION_TARGET_TYPEMASK_VZ_IGNOREIgnore velocity z
64POSITION_TARGET_TYPEMASK_AX_IGNOREIgnore acceleration x
128POSITION_TARGET_TYPEMASK_AY_IGNOREIgnore acceleration y
256POSITION_TARGET_TYPEMASK_AZ_IGNOREIgnore acceleration z
512POSITION_TARGET_TYPEMASK_FORCE_SETUse force instead of acceleration
1024POSITION_TARGET_TYPEMASK_YAW_IGNOREIgnore yaw
2048POSITION_TARGET_TYPEMASK_YAW_RATE_IGNOREIgnore yaw rate

UTM_FLIGHT_STATE

Airborne status of UAS.

ValueField NameDescription
1UTM_FLIGHT_STATE_UNKNOWNThe flight state can't be determined.
2UTM_FLIGHT_STATE_GROUNDUAS on ground.
3UTM_FLIGHT_STATE_AIRBORNEUAS airborne.
16UTM_FLIGHT_STATE_EMERGENCYUAS is in an emergency flight state.
32UTM_FLIGHT_STATE_NOCTRLUAS has no active controls.

UTM_DATA_AVAIL_FLAGS

Flags for the global position report.

ValueField NameDescription
1UTM_DATA_AVAIL_FLAGS_TIME_VALIDThe field time contains valid data.
2UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLEThe field uas_id contains valid data.
4UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLEThe fields lat, lon and h_acc contain valid data.
8UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLEThe fields alt and v_acc contain valid data.
16UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLEThe field relative_alt contains valid data.
32UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLEThe fields vx and vy contain valid data.
64UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLEThe field vz contains valid data.
128UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLEThe fields next_lat, next_lon and next_alt contain valid data.

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.

MAV_CMD_NAV_WAYPOINT (16 )

Navigate to waypoint.

ParamDescription
1Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)
2Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)
30 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.
4Desired yaw angle at waypoint (rotary wing). NaN for unchanged.
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_LOITER_UNLIM (17 )

Loiter around this waypoint an unlimited amount of time

ParamDescription
1Empty
2Empty
3Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise
4Desired yaw angle.
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_LOITER_TURNS (18 )

Loiter around this waypoint for X turns

ParamDescription
1Turns
2Empty
3Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise
4Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_LOITER_TIME (19 )

Loiter around this waypoint for X seconds

ParamDescription
1Seconds (decimal)
2Empty
3Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise
4Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location. Else, this is desired yaw angle
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_RETURN_TO_LAUNCH (20 )

Return to launch location

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_NAV_LAND (21 )

Land at location

ParamDescription
1Abort Alt
2Precision land mode. (0 = normal landing, 1 = opportunistic precision landing, 2 = required precsion landing)
3Empty
4Desired yaw angle. NaN for unchanged.
5Latitude
6Longitude
7Altitude (ground level)

MAV_CMD_NAV_TAKEOFF (22 )

Takeoff from ground / hand

ParamDescription
1Minimum pitch (if airspeed sensor present), desired pitch without sensor
2Empty
3Empty
4Yaw angle (if magnetometer present), ignored without magnetometer. NaN for unchanged.
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_LAND_LOCAL (23 )

Land at local position (local frame only)

ParamDescription
1Landing target number (if available)
2Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land
3Landing descend rate [ms^-1]
4Desired yaw angle [rad]
5Y-axis position [m]
6X-axis position [m]
7Z-axis / ground level position [m]

MAV_CMD_NAV_TAKEOFF_LOCAL (24 )

Takeoff from local position (local frame only)

ParamDescription
1Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]
2Empty
3Takeoff ascend rate [ms^-1]
4Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these
5Y-axis position [m]
6X-axis position [m]
7Z-axis position [m]

MAV_CMD_NAV_FOLLOW (25 )

Vehicle following, i.e. this waypoint represents the position of a moving vehicle

ParamDescription
1Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation
2Ground speed of vehicle to be followed
3Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise
4Desired yaw angle.
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT (30 )

Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.

ParamDescription
1Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.
2Empty
3Empty
4Empty
5Empty
6Empty
7Desired altitude in meters

MAV_CMD_NAV_LOITER_TO_ALT (31 )

Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint.

ParamDescription
1Heading Required (0 = False)
2Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.
3Empty
4Forward moving aircraft this sets exit xtrack location: 0 for center of loiter wp, 1 for exit location
5Latitude
6Longitude
7Altitude

MAV_CMD_DO_FOLLOW (32 )

Being following a target

ParamDescription
1System ID (the system ID of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode
2RESERVED
3RESERVED
4altitude flag: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home
5altitude
6RESERVED
7TTL in seconds in which the MAV should go to the default position hold mode after a message rx timeout

MAV_CMD_DO_FOLLOW_REPOSITION (33 )

Reposition the MAV after a follow target command has been sent

ParamDescription
1Camera q1 (where 0 is on the ray from the camera to the tracking device)
2Camera q2
3Camera q3
4Camera q4
5altitude offset from target (m)
6X offset from target (m)
7Y offset from target (m)

MAV_CMD_DO_ORBIT (34 )

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

Start orbiting on the circumference of a circle defined by the parameters. Setting any value NaN results in using defaults.

ParamDescription
1Radius of the circle in meters. positive: Orbit clockwise. negative: Orbit counter-clockwise.
2Velocity tangential in m/s. NaN: Vehicle configuration default.
3Yaw behavior of the vehicle. 0: vehicle front points to the center (default). 1: Hold last heading. 2: Leave yaw uncontrolled.
4Reserved (e.g. for dynamic center beacon options)
5Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.
6Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.
7Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle position or current center if already orbiting.

MAV_CMD_NAV_ROI (80 )

DEPRECATED: Replaced by MAV_CMD_DO_SET_ROI_* (2018-01).

Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

ParamDescription
1Region of interest mode. (see MAV_ROI enum)
2Waypoint index/ target ID. (see MAV_ROI enum)
3ROI index (allows a vehicle to manage multiple ROI's)
4Empty
5x the location of the fixed ROI (see MAV_FRAME)
6y
7z

MAV_CMD_NAV_PATHPLANNING (81 )

Control autonomous path planning on the MAV.

ParamDescription
10: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning
20: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid
3Empty
4Yaw angle at goal, in compass degrees, [0..360]
5Latitude/X of goal
6Longitude/Y of goal
7Altitude/Z of goal

MAV_CMD_NAV_SPLINE_WAYPOINT (82 )

Navigate to waypoint using a spline path.

ParamDescription
1Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)
2Empty
3Empty
4Empty
5Latitude/X of goal
6Longitude/Y of goal
7Altitude/Z of goal

MAV_CMD_NAV_VTOL_TAKEOFF (84 )

Takeoff from ground using VTOL mode

ParamDescription
1Empty
2Front transition heading, see VTOL_TRANSITION_HEADING enum.
3Empty
4Yaw angle in degrees. NaN for unchanged.
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_VTOL_LAND (85 )

Land using VTOL mode

ParamDescription
1Empty
2Empty
3Approach altitude (with the same reference as the Altitude field). NaN if unspecified.
4Yaw angle in degrees. NaN for unchanged.
5Latitude
6Longitude
7Altitude (ground level)

MAV_CMD_NAV_GUIDED_ENABLE (92 )

hand control over to an external controller

ParamDescription
1On / Off (> 0.5f on)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_NAV_DELAY (93 )

Delay the next navigation command a number of seconds or until a specified time

ParamDescription
1Delay in seconds (decimal, -1 to enable time-of-day fields)
2hour (24h format, UTC, -1 to ignore)
3minute (24h format, UTC, -1 to ignore)
4second (24h format, UTC)
5Empty
6Empty
7Empty

MAV_CMD_NAV_PAYLOAD_PLACE (94 )

Descend and place payload. Vehicle descends until it detects a hanging payload has reached the ground, the gripper is opened to release the payload

ParamDescription
1Maximum distance to descend (meters)
2Empty
3Empty
4Empty
5Latitude (deg * 1E7)
6Longitude (deg * 1E7)
7Altitude (meters)

MAV_CMD_NAV_LAST (95 )

NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_DELAY (112 )

Delay mission state machine.

ParamDescription
1Delay in seconds (decimal)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_CHANGE_ALT (113 )

Ascend/descend at rate. Delay mission state machine until desired altitude reached.

ParamDescription
1Descent / Ascend rate (m/s)
2Empty
3Empty
4Empty
5Empty
6Empty
7Finish Altitude

MAV_CMD_CONDITION_DISTANCE (114 )

Delay mission state machine until within desired distance of next NAV point.

ParamDescription
1Distance (meters)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_YAW (115 )

Reach a certain target angle.

ParamDescription
1target angle: [0-360], 0 is north
2speed during yaw change:[deg per second]
3direction: negative: counter clockwise, positive: clockwise [-1,1]
4relative offset or absolute angle: [ 1,0]
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_LAST (159 )

NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_MODE (176 )

Set system mode.

ParamDescription
1Mode, as defined by ENUM MAV_MODE
2Custom mode - this is system specific, please refer to the individual autopilot specifications for details.
3Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_JUMP (177 )

Jump to the desired command in the mission list. Repeat this action only the specified number of times

ParamDescription
1Sequence number
2Repeat count
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_CHANGE_SPEED (178 )

Change speed and/or throttle set points.

ParamDescription
1Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)
2Speed (m/s, -1 indicates no change)
3Throttle ( Percent, -1 indicates no change)
4absolute or relative [0,1]
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_HOME (179 )

Changes the home location either to the current location or a specified location.

ParamDescription
1Use current (1=use current location, 0=use specified location)
2Empty
3Empty
4Empty
5Latitude
6Longitude
7Altitude

MAV_CMD_DO_SET_PARAMETER (180 )

Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.

ParamDescription
1Parameter number
2Parameter value
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_RELAY (181 )

Set a relay to a condition.

ParamDescription
1Relay number
2Setting (1=on, 0=off, others possible depending on system hardware)
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPEAT_RELAY (182 )

Cycle a relay on and off for a desired number of cycles with a desired period.

ParamDescription
1Relay number
2Cycle count
3Cycle time (seconds, decimal)
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_SERVO (183 )

Set a servo to a desired PWM value.

ParamDescription
1Servo number
2PWM (microseconds, 1000 to 2000 typical)
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPEAT_SERVO (184 )

Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.

ParamDescription
1Servo number
2PWM (microseconds, 1000 to 2000 typical)
3Cycle count
4Cycle time (seconds)
5Empty
6Empty
7Empty

MAV_CMD_DO_FLIGHTTERMINATION (185 )

Terminate flight immediately

ParamDescription
1Flight termination activated if > 0.5
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_CHANGE_ALTITUDE (186 )

Change altitude set point.

ParamDescription
1Altitude in meters
2Mav frame of new altitude (see MAV_FRAME)
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_LAND_START (189 )

Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0 if not needed. If specified then it will be used to help find the closest landing sequence.

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Latitude
6Longitude
7Empty

MAV_CMD_DO_RALLY_LAND (190 )

Mission command to perform a landing from a rally point.

ParamDescription
1Break altitude (meters)
2Landing speed (m/s)
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_GO_AROUND (191 )

Mission command to safely abort an autonomous landing.

ParamDescription
1Altitude (meters)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPOSITION (192 )

Reposition the vehicle to a specific WGS84 global position.

ParamDescription
1Ground speed, less than 0 (-1) for default
2Bitmask of option flags, see the MAV_DO_REPOSITION_FLAGS enum.
3Reserved
4Yaw heading, NaN for unchanged. For planes indicates loiter direction (0: clockwise, 1: counter clockwise)
5Latitude (deg * 1E7)
6Longitude (deg * 1E7)
7Altitude (meters)

MAV_CMD_DO_PAUSE_CONTINUE (193 )

If in a GPS controlled position mode, hold the current position or continue.

ParamDescription
10: Pause current mission or reposition command, hold current position. 1: Continue mission. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_DO_SET_REVERSE (194 )

Set moving direction to forward or reverse.

ParamDescription
1Direction (0=Forward, 1=Reverse)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ROI_LOCATION (195 )

Sets the region of interest (ROI) to a location. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Latitude
6Longitude
7Altitude

MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET (196 )

Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

ParamDescription
1Empty
2Empty
3Empty
4Empty
5pitch offset from next waypoint
6roll offset from next waypoint
7yaw offset from next waypoint

MAV_CMD_DO_SET_ROI_NONE (197 )

Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_CONTROL_VIDEO (200 )

Control onboard camera system.

ParamDescription
1Camera ID (-1 for all)
2Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw
3Transmission mode: 0: video stream, >0: single images every n seconds (decimal)
4Recording: 0: disabled, 1: enabled compressed, 2: enabled raw
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ROI (201 )

DEPRECATED: Replaced by MAV_CMD_DO_SET_ROI_* (2018-01).

Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.

ParamDescription
1Region of interest mode. (see MAV_ROI enum)
2Waypoint index/ target ID. (see MAV_ROI enum)
3ROI index (allows a vehicle to manage multiple ROI's)
4Empty
5MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude
6MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude
7MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude

MAV_CMD_DO_DIGICAM_CONFIGURE (202 )

THIS INTERFACE IS DEPRECATED since 2018-01. Please use PARAM_EXT_XXX messages and the camera definition format described in https://mavlink.io/en/protocol/camera_def.html.

ParamDescription
1Modes: P, TV, AV, M, Etc
2Shutter speed: Divisor number for one second
3Aperture: F stop number
4ISO number e.g. 80, 100, 200, Etc
5Exposure type enumerator
6Command Identity
7Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)

MAV_CMD_DO_DIGICAM_CONTROL (203 )

THIS INTERFACE IS DEPRECATED since 2018-01. Please use PARAM_EXT_XXX messages and the camera definition format described in https://mavlink.io/en/protocol/camera_def.html.

ParamDescription
1Session control e.g. show/hide lens
2Zoom's absolute position
3Zooming step value to offset zoom from the current position
4Focus Locking, Unlocking or Re-locking
5Shooting Command
6Command Identity
7Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.

MAV_CMD_DO_MOUNT_CONFIGURE (204 )

Mission command to configure a camera or antenna mount

ParamDescription
1Mount operation mode (see MAV_MOUNT_MODE enum)
2stabilize roll? (1 = yes, 0 = no)
3stabilize pitch? (1 = yes, 0 = no)
4stabilize yaw? (1 = yes, 0 = no)
5roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
6pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
7yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)

MAV_CMD_DO_MOUNT_CONTROL (205 )

Mission command to control a camera or antenna mount

ParamDescription
1pitch depending on mount mode (degrees or degrees/second depending on pitch input).
2roll depending on mount mode (degrees or degrees/second depending on roll input).
3yaw depending on mount mode (degrees or degrees/second depending on yaw input).
4alt in meters depending on mount mode.
5latitude in degrees * 1E7, set if appropriate mount mode.
6longitude in degrees * 1E7, set if appropriate mount mode.
7MAV_MOUNT_MODE enum value

MAV_CMD_DO_SET_CAM_TRIGG_DIST (206 )

Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera.

ParamDescription
1Camera trigger distance (meters). 0 to stop triggering.
2Camera shutter integration time (milliseconds). -1 or 0 to ignore
3Trigger camera once immediately. (0 = no trigger, 1 = trigger)
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_FENCE_ENABLE (207 )

Mission command to enable the geofence

ParamDescription
1enable? (0=disable, 1=enable, 2=disable_floor_only)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_PARACHUTE (208 )

Mission command to trigger a parachute

ParamDescription
1action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_MOTOR_TEST (209 )

Mission command to perform motor test

ParamDescription
1motor number (a number from 1 to max number of motors on the vehicle)
2throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
3throttle
4timeout (in seconds)
5motor count (number of motors to test to test in sequence, waiting for the timeout above between them; 0=1 motor, 1=1 motor, 2=2 motors...)
6motor test order (See MOTOR_TEST_ORDER enum)
7Empty

MAV_CMD_DO_INVERTED_FLIGHT (210 )

Change to/from inverted flight

ParamDescription
1inverted (0=normal, 1=inverted)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_NAV_SET_YAW_SPEED (213 )

Sets a desired vehicle turn angle and speed change

ParamDescription
1yaw angle to adjust steering by in centidegress
2speed - normalized to 0 .. 1
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL (214 )

Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera.

ParamDescription
1Camera trigger cycle time (milliseconds). -1 or 0 to ignore.
2Camera shutter integration time (milliseconds). Should be less than trigger cycle time. -1 or 0 to ignore.
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_MOUNT_CONTROL_QUAT (220 )

Mission command to control a camera or antenna mount, using a quaternion as reference.

ParamDescription
1q1 - quaternion param #1, w (1 in null-rotation)
2q2 - quaternion param #2, x (0 in null-rotation)
3q3 - quaternion param #3, y (0 in null-rotation)
4q4 - quaternion param #4, z (0 in null-rotation)
5Empty
6Empty
7Empty

MAV_CMD_DO_GUIDED_MASTER (221 )

set id of master controller

ParamDescription
1System ID
2Component ID
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_GUIDED_LIMITS (222 )

Set limits for external control

ParamDescription
1Timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout.
2Altitude (MSL) min, in meters - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.
3Altitude (MSL) max, in meters - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.
4Horizontal move limit, in meters - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.
5Empty
6Empty
7Empty

MAV_CMD_DO_ENGINE_CONTROL (223 )

Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines

ParamDescription
10: Stop engine, 1:Start Engine
20: Warm start, 1:Cold start. Controls use of choke where applicable
3Height delay (meters). This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.
4Empty
5Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_MISSION_CURRENT (224 )

Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).

ParamDescription
1Mission sequence value to set
2Empty
3Empty
4Empty
5Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_LAST (240 )

NOP - This command is only used to mark the upper limit of the DO commands in the enumeration

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_PREFLIGHT_CALIBRATION (241 )

Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero.

ParamDescription
11: gyro calibration, 3: gyro temperature calibration
21: magnetometer calibration
31: ground pressure calibration
41: radio RC calibration, 2: RC trim calibration
51: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration
61: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration
71: ESC calibration, 3: barometer temperature calibration

MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (242 )

Set sensor offsets. This command will be only accepted if in pre-flight mode.

ParamDescription
1Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer
2X axis offset (or generic dimension 1), in the sensor's raw units
3Y axis offset (or generic dimension 2), in the sensor's raw units
4Z axis offset (or generic dimension 3), in the sensor's raw units
5Generic dimension 4, in the sensor's raw units
6Generic dimension 5, in the sensor's raw units
7Generic dimension 6, in the sensor's raw units

MAV_CMD_PREFLIGHT_UAVCAN (243 )

Trigger UAVCAN config. This command will be only accepted if in pre-flight mode.

ParamDescription
11: Trigger actuator ID assignment and direction mapping.
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_PREFLIGHT_STORAGE (245 )

Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.

ParamDescription
1Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults
2Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults
3Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)
4Reserved
5Empty
6Empty
7Empty

MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246 )

Request the reboot or shutdown of system components.

ParamDescription
10: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.
20: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer, 3: Reboot onboard computer and keep it in the bootloader until upgraded.
3WIP: 0: Do nothing for camera, 1: Reboot onboard camera, 2: Shutdown onboard camera, 3: Reboot onboard camera and keep it in the bootloader until upgraded
4WIP: 0: Do nothing for mount (e.g. gimbal), 1: Reboot mount, 2: Shutdown mount, 3: Reboot mount and keep it in the bootloader until upgraded
5Reserved, send 0
6Reserved, send 0
7WIP: ID (e.g. camera ID -1 for all IDs)

MAV_CMD_OVERRIDE_GOTO (252 )

Hold / continue the current action

ParamDescription
1MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan
2MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position
3MAV_FRAME coordinate frame of hold point
4Desired yaw angle in degrees
5Latitude / X position
6Longitude / Y position
7Altitude / Z position

MAV_CMD_MISSION_START (300 )

start running a mission

ParamDescription
1first_item: the first mission item to run
2last_item: the last mission item to run (after this item is run, the mission ends)

MAV_CMD_COMPONENT_ARM_DISARM (400 )

Arms / Disarms a component

ParamDescription
11 to arm, 0 to disarm

MAV_CMD_GET_HOME_POSITION (410 )

Request the home position from the vehicle.

ParamDescription
1Reserved
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_START_RX_PAIR (500 )

Starts receiver pairing

ParamDescription
10:Spektrum
2RC type (see RC_TYPE enum)

MAV_CMD_GET_MESSAGE_INTERVAL (510 )

Request the interval between messages for a particular MAVLink message ID

ParamDescription
1The MAVLink message ID

MAV_CMD_SET_MESSAGE_INTERVAL (511 )

Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM

ParamDescription
1The MAVLink message ID
2The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.

MAV_CMD_REQUEST_PROTOCOL_VERSION (519 )

Request MAVLink protocol version compatibility

ParamDescription
11: Request supported protocol versions by all nodes on the network
2Reserved (all remaining params)

MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (520 )

Request autopilot capabilities

ParamDescription
11: Request autopilot version
2Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_INFORMATION (521 )

Request camera information (CAMERA_INFORMATION).

ParamDescription
10: No action 1: Request camera capabilities
2Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_SETTINGS (522 )

Request camera settings (CAMERA_SETTINGS).

ParamDescription
10: No Action 1: Request camera settings
2Reserved (all remaining params)

MAV_CMD_REQUEST_STORAGE_INFORMATION (525 )

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

Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage.

ParamDescription
1Storage ID (0 for all, 1 for first, 2 for second, etc.)
20: No Action 1: Request storage information
3Reserved (all remaining params)

MAV_CMD_STORAGE_FORMAT (526 )

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

Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage.

ParamDescription
1Storage ID (1 for first, 2 for second, etc.)
20: No action 1: Format storage
3Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (527 )

Request camera capture status (CAMERA_CAPTURE_STATUS)

ParamDescription
10: No Action 1: Request camera capture status
2Reserved (all remaining params)

MAV_CMD_REQUEST_FLIGHT_INFORMATION (528 )

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

Request flight information (FLIGHT_INFORMATION)

ParamDescription
11: Request flight information
2Reserved (all remaining params)

MAV_CMD_RESET_CAMERA_SETTINGS (529 )

Reset all camera settings to Factory Default

ParamDescription
10: No Action 1: Reset all settings
2Reserved (all remaining params)

MAV_CMD_SET_CAMERA_MODE (530 )

Set camera running mode. Use NAN for reserved values.

ParamDescription
1Reserved (Set to 0)
2Camera mode (see CAMERA_MODE enum)
3Reserved (all remaining params)

MAV_CMD_SET_CAMERA_ZOOM (531 )

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

Set camera zoom. Returns CAMERA_SETTINGS message. Use NAN for reserved values.

ParamDescriptionValues
1Zoom typeSET_ZOOM_TYPE
2Zoom value
3Reserved (all remaining params)

MAV_CMD_SET_CAMERA_FOCUS (532 )

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

Set camera focus. Returns CAMERA_SETTINGS message. Use NAN for reserved values.

ParamDescriptionValues
1Focus typeSET_FOCUS_TYPE
2Focus value
3Reserved (all remaining params)

MAV_CMD_IMAGE_START_CAPTURE (2000 )

Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture. Use NAN for reserved values.

ParamDescription
1Reserved (Set to 0)
2Duration between two consecutive pictures (in seconds)
3Number of images to capture total - 0 for unlimited capture
4Capture sequence (ID to prevent double captures when a command is retransmitted, 0: unused, >= 1: used)
5Reserved (all remaining params)

MAV_CMD_IMAGE_STOP_CAPTURE (2001 )

Stop image capture sequence Use NAN for reserved values.

ParamDescription
1Reserved (Set to 0)
2Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE (2002 )

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

Re-request a CAMERA_IMAGE_CAPTURE packet. Use NAN for reserved values.

ParamDescription
1Sequence number for missing CAMERA_IMAGE_CAPTURE packet
2Reserved (all remaining params)

MAV_CMD_DO_TRIGGER_CONTROL (2003 )

Enable or disable on-board camera triggering system.

ParamDescription
1Trigger enable/disable (0 for disable, 1 for start), -1 to ignore
21 to reset the trigger sequence, -1 or 0 to ignore
31 to pause triggering, but without switching the camera off or retracting it. -1 to ignore

MAV_CMD_VIDEO_START_CAPTURE (2500 )

Starts video capture (recording). Use NAN for reserved values.

ParamDescription
1Reserved (Set to 0)
2Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency in Hz)
3Reserved (all remaining params)

MAV_CMD_VIDEO_STOP_CAPTURE (2501 )

Stop the current video capture (recording). Use NAN for reserved values.

ParamDescription
1Reserved (Set to 0)
2Reserved (all remaining params)

MAV_CMD_VIDEO_START_STREAMING (2502 )

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

Start video streaming

ParamDescription
1Stream ID (0 for all streams, 1 for first, 2 for second, etc.)
2Reserved

MAV_CMD_VIDEO_STOP_STREAMING (2503 )

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

Stop the current video streaming

ParamDescription
1Stream ID (0 for all streams, 1 for first, 2 for second, etc.)
2Reserved

MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (2504 )

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

Request video stream information (VIDEO_STREAM_INFORMATION)

ParamDescription
1Stream ID (0 for all streams, 1 for first, 2 for second, etc.)
20: No Action 1: Request video stream information
3Reserved (all remaining params)

MAV_CMD_LOGGING_START (2510 )

Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)

ParamDescription
1Format: 0: ULog
2Reserved (set to 0)
3Reserved (set to 0)
4Reserved (set to 0)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_LOGGING_STOP (2511 )

Request to stop streaming log data over MAVLink

ParamDescription
1Reserved (set to 0)
2Reserved (set to 0)
3Reserved (set to 0)
4Reserved (set to 0)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_AIRFRAME_CONFIGURATION (2520 )

ParamDescription
1Landing gear ID (default: 0, -1 for all)
2Landing gear position (Down: 0, Up: 1, NAN for no change)
3Reserved, set to NAN
4Reserved, set to NAN
5Reserved, set to NAN
6Reserved, set to NAN
7Reserved, set to NAN

MAV_CMD_CONTROL_HIGH_LATENCY (2600 )

Request to start/stop transmitting over the high latency telemetry

ParamDescription
1Control transmission over high latency telemetry (0: stop, 1: start)
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_PANORAMA_CREATE (2800 )

Create a panorama at the current position

ParamDescription
1Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)
2Viewing angle vertical of panorama (in degrees)
3Speed of the horizontal rotation (in degrees per second)
4Speed of the vertical rotation (in degrees per second)

MAV_CMD_DO_VTOL_TRANSITION (3000 )

Request VTOL transition

ParamDescription
1The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.

MAV_CMD_ARM_AUTHORIZATION_REQUEST (3001 )

Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON.

ParamDescription
1Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle

MAV_CMD_SET_GUIDED_SUBMODE_STANDARD (4000 )

This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.

ParamDescription

MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE (4001 )

This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.

ParamDescription
1Radius of desired circle in CIRCLE_MODE
2User defined
3User defined
4User defined
5Unscaled target latitude of center of circle in CIRCLE_MODE
6Unscaled target longitude of center of circle in CIRCLE_MODE

MAV_CMD_CONDITION_GATE (4501 )

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

Delay mission state machine until gate has been reached.

ParamDescription
1Geometry: 0: orthogonal to path between previous and next waypoint.
2Altitude: 0: ignore altitude
3Empty
4Empty
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_FENCE_RETURN_POINT (5000 )

Fence return point. There can only be one fence return point.

ParamDescription
1Reserved
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Altitude

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION (5001 )

Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required.

ParamDescription
1Polygon vertex count
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Reserved

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION (5002 )

Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.

ParamDescription
1Polygon vertex count
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Reserved

MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION (5003 )

Circular fence area. The vehicle must stay inside this area.

ParamDescription
1radius in meters
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Reserved

MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION (5004 )

Circular fence area. The vehicle must stay outside this area.

ParamDescription
1radius in meters
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Reserved

MAV_CMD_NAV_RALLY_POINT (5100 )

Rally point. You can have multiple rally points defined.

ParamDescription
1Reserved
2Reserved
3Reserved
4Reserved
5Latitude
6Longitude
7Altitude

MAV_CMD_UAVCAN_GET_NODE_INFO (5200 )

Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages.

ParamDescription
1Reserved (set to 0)
2Reserved (set to 0)
3Reserved (set to 0)
4Reserved (set to 0)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_PAYLOAD_PREPARE_DEPLOY (30001 )

Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.

ParamDescription
1Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.
2Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.
3Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.
4Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.
5Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT
6Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT
7Altitude (MSL), in meters

MAV_CMD_PAYLOAD_CONTROL_DEPLOY (30002 )

Control the payload deployment.

ParamDescription
1Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_WAYPOINT_USER_1 (31000 )

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_WAYPOINT_USER_2 (31001 )

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_WAYPOINT_USER_3 (31002 )

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_WAYPOINT_USER_4 (31003 )

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_WAYPOINT_USER_5 (31004 )

User defined waypoint item. Ground Station will show the Vehicle as flying through this item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_SPATIAL_USER_1 (31005 )

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_SPATIAL_USER_2 (31006 )

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_SPATIAL_USER_3 (31007 )

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_SPATIAL_USER_4 (31008 )

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_SPATIAL_USER_5 (31009 )

User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5Latitude unscaled
6Longitude unscaled
7Altitude (MSL), in meters

MAV_CMD_USER_1 (31010 )

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_2 (31011 )

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_3 (31012 )

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_4 (31013 )

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_5 (31014 )

User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item.

ParamDescription
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

HEARTBEAT ( #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).

Field NameTypeValuesDescription
typeuint8_tMAV_TYPEType of the system (quadrotor, helicopter, etc.). Components use the same type as their associated system.
autopilotuint8_tMAV_AUTOPILOTAutopilot type / class.
base_modeuint8_tMAV_MODE_FLAGSystem mode bitmap.
custom_modeuint32_tA bitfield for use for autopilot-specific flags
system_statusuint8_tMAV_STATESystem status flag.
mavlink_versionuint8_t_mavlink_versionMAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version

SYS_STATUS ( #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.

Field NameTypeUnitsValuesDescription
onboard_control_sensors_presentuint32_tMAV_SYS_STATUS_SENSORBitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
onboard_control_sensors_enableduint32_tMAV_SYS_STATUS_SENSORBitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
onboard_control_sensors_healthuint32_tMAV_SYS_STATUS_SENSORBitmap showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled.
loaduint16_td%Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
voltage_batteryuint16_tmVBattery voltage
current_batteryint16_tcABattery current, -1: autopilot does not measure the current
battery_remainingint8_t%Remaining battery energy, -1: autopilot estimate the remaining battery
drop_rate_commuint16_tc%Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
errors_commuint16_tCommunication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
errors_count1uint16_tAutopilot-specific errors
errors_count2uint16_tAutopilot-specific errors
errors_count3uint16_tAutopilot-specific errors
errors_count4uint16_tAutopilot-specific errors

SYSTEM_TIME ( #2 )

The system time is the time of the master clock, typically the computer clock of the main onboard computer.

Field NameTypeUnitsDescription
time_unix_usecuint64_tusTimestamp (UNIX epoch time).
time_boot_msuint32_tmsTimestamp (time since system boot).

PING ( #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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
sequint32_tPING sequence
target_systemuint8_t0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system
target_componentuint8_t0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component.

CHANGE_OPERATOR_CONTROL ( #5 )

Request to control this MAV

Field NameTypeUnitsDescription
target_systemuint8_tSystem the GCS requests control for
control_requestuint8_t0: request control of this MAV, 1: Release control of this MAV
versionuint8_trad0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
passkeychar[25]Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"

CHANGE_OPERATOR_CONTROL_ACK ( #6 )

Accept / deny control of this MAV

Field NameTypeDescription
gcs_system_iduint8_tID of the GCS this message
control_requestuint8_t0: request control of this MAV, 1: Release control of this MAV
ackuint8_t0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control

AUTH_KEY ( #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.

Field NameTypeDescription
keychar[32]key

SET_MODE ( #11 )

DEPRECATED: Replaced by MAV_CMD_DO_SET_MODE (2015-12). Use COMMAND_LONG with MAV_CMD_DO_SET_MODE instead

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.

Field NameTypeValuesDescription
target_systemuint8_tThe system setting the mode
base_modeuint8_tMAV_MODEThe new base mode.
custom_modeuint32_tThe new autopilot-specific mode. This field can be ignored by an autopilot.

PARAM_REQUEST_READ ( #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/protocol/parameter.html for a full documentation of QGroundControl and IMU code.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
param_idchar[16]Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexint16_tParameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)

PARAM_REQUEST_LIST ( #21 )

Request all parameters of this component. After this request, all parameters are emitted.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

PARAM_VALUE ( #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.

Field NameTypeValuesDescription
param_idchar[16]Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_valuefloatOnboard parameter value
param_typeuint8_tMAV_PARAM_TYPEOnboard parameter type.
param_countuint16_tTotal number of onboard parameters
param_indexuint16_tIndex of this onboard parameter

PARAM_SET ( #23 )

Set a parameter value (write new value to permanent storage). IMPORTANT: The receiving component should acknowledge the new parameter value by sending a PARAM_VALUE message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
param_idchar[16]Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_valuefloatOnboard parameter value
param_typeuint8_tMAV_PARAM_TYPEOnboard parameter type.

GPS_RAW_INT ( #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 for the global position estimate.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
fix_typeuint8_tGPS_FIX_TYPEGPS fix type.
latint32_tdegE7Latitude (WGS84, EGM96 ellipsoid)
lonint32_tdegE7Longitude (WGS84, EGM96 ellipsoid)
altint32_tmmAltitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
ephuint16_tGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
epvuint16_tGPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
veluint16_tcm/sGPS ground speed. If unknown, set to: UINT16_MAX
coguint16_tcdegCourse over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
satellites_visibleuint8_tNumber of satellites visible. If unknown, set to 255
alt_ellipsoid **int32_tmmAltitude (above WGS84, EGM96 ellipsoid). Positive for up.
h_acc **uint32_tmmPosition uncertainty. Positive for up.
v_acc **uint32_tmmAltitude uncertainty. Positive for up.
vel_acc **uint32_tmmSpeed uncertainty. Positive for up.
hdg_acc **uint32_tdegE5Heading / track uncertainty

GPS_STATUS ( #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 for the global position estimate. This message can contain information for up to 20 satellites.

Field NameTypeUnitsDescription
satellites_visibleuint8_tNumber of satellites visible
satellite_prnuint8_t[20]Global satellite ID
satellite_useduint8_t[20]0: Satellite not used, 1: used for localization
satellite_elevationuint8_t[20]degElevation (0: right on top of receiver, 90: on the horizon) of satellite
satellite_azimuthuint8_t[20]degDirection of satellite, 0: 0 deg, 255: 360 deg.
satellite_snruint8_t[20]dBSignal to noise ratio of satellite

SCALED_IMU ( #26 )

The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
xaccint16_tmGX acceleration
yaccint16_tmGY acceleration
zaccint16_tmGZ acceleration
xgyroint16_tmrad/sAngular speed around X axis
ygyroint16_tmrad/sAngular speed around Y axis
zgyroint16_tmrad/sAngular speed around Z axis
xmagint16_tmTX Magnetic field
ymagint16_tmTY Magnetic field
zmagint16_tmTZ Magnetic field

RAW_IMU ( #27 )

The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
xaccint16_tX acceleration (raw)
yaccint16_tY acceleration (raw)
zaccint16_tZ acceleration (raw)
xgyroint16_tAngular speed around X axis (raw)
ygyroint16_tAngular speed around Y axis (raw)
zgyroint16_tAngular speed around Z axis (raw)
xmagint16_tX Magnetic field (raw)
ymagint16_tY Magnetic field (raw)
zmagint16_tZ Magnetic field (raw)

RAW_PRESSURE ( #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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
press_absint16_tAbsolute pressure (raw)
press_diff1int16_tDifferential pressure 1 (raw, 0 if nonexistent)
press_diff2int16_tDifferential pressure 2 (raw, 0 if nonexistent)
temperatureint16_tRaw Temperature measurement (raw)

SCALED_PRESSURE ( #29 )

The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
press_absfloathPaAbsolute pressure
press_difffloathPaDifferential pressure 1
temperatureint16_tcdegCTemperature

ATTITUDE ( #30 )

The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
rollfloatradRoll angle (-pi..+pi)
pitchfloatradPitch angle (-pi..+pi)
yawfloatradYaw angle (-pi..+pi)
rollspeedfloatrad/sRoll angular speed
pitchspeedfloatrad/sPitch angular speed
yawspeedfloatrad/sYaw angular speed

ATTITUDE_QUATERNION ( #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).

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
q1floatQuaternion component 1, w (1 in null-rotation)
q2floatQuaternion component 2, x (0 in null-rotation)
q3floatQuaternion component 3, y (0 in null-rotation)
q4floatQuaternion component 4, z (0 in null-rotation)
rollspeedfloatrad/sRoll angular speed
pitchspeedfloatrad/sPitch angular speed
yawspeedfloatrad/sYaw angular speed

LOCAL_POSITION_NED ( #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)

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
xfloatmX Position
yfloatmY Position
zfloatmZ Position
vxfloatm/sX Speed
vyfloatm/sY Speed
vzfloatm/sZ Speed

GLOBAL_POSITION_INT ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
latint32_tdegE7Latitude, expressed
lonint32_tdegE7Longitude, expressed
altint32_tmmAltitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
relative_altint32_tmmAltitude above ground
vxint16_tcm/sGround X Speed (Latitude, positive north)
vyint16_tcm/sGround Y Speed (Longitude, positive east)
vzint16_tcm/sGround Z Speed (Altitude, positive down)
hdguint16_tcdegVehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX

RC_CHANNELS_SCALED ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
portuint8_tServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
chan1_scaledint16_tRC channel 1 value scaled.
chan2_scaledint16_tRC channel 2 value scaled.
chan3_scaledint16_tRC channel 3 value scaled.
chan4_scaledint16_tRC channel 4 value scaled.
chan5_scaledint16_tRC channel 5 value scaled.
chan6_scaledint16_tRC channel 6 value scaled.
chan7_scaledint16_tRC channel 7 value scaled.
chan8_scaledint16_tRC channel 8 value scaled.
rssiuint8_t%Receive signal strength indicator. Values: [0-100], 255: invalid/unknown.

RC_CHANNELS_RAW ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
portuint8_tServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
chan1_rawuint16_tusRC channel 1 value.
chan2_rawuint16_tusRC channel 2 value.
chan3_rawuint16_tusRC channel 3 value.
chan4_rawuint16_tusRC channel 4 value.
chan5_rawuint16_tusRC channel 5 value.
chan6_rawuint16_tusRC channel 6 value.
chan7_rawuint16_tusRC channel 7 value.
chan8_rawuint16_tusRC channel 8 value.
rssiuint8_t%Receive signal strength indicator. Values: [0-100], 255: invalid/unknown.

SERVO_OUTPUT_RAW ( #36 )

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

Field NameTypeUnitsDescription
time_usecuint32_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
portuint8_tServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
servo1_rawuint16_tusServo output 1 value
servo2_rawuint16_tusServo output 2 value
servo3_rawuint16_tusServo output 3 value
servo4_rawuint16_tusServo output 4 value
servo5_rawuint16_tusServo output 5 value
servo6_rawuint16_tusServo output 6 value
servo7_rawuint16_tusServo output 7 value
servo8_rawuint16_tusServo output 8 value
servo9_raw **uint16_tusServo output 9 value
servo10_raw **uint16_tusServo output 10 value
servo11_raw **uint16_tusServo output 11 value
servo12_raw **uint16_tusServo output 12 value
servo13_raw **uint16_tusServo output 13 value
servo14_raw **uint16_tusServo output 14 value
servo15_raw **uint16_tusServo output 15 value
servo16_raw **uint16_tusServo output 16 value

MISSION_REQUEST_PARTIAL_LIST ( #37 )

Request a partial list of mission items from the system/component. https://mavlink.io/en/protocol/mission.html. If start and end index are the same, just send one waypoint.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
start_indexint16_tStart index, 0 by default
end_indexint16_tEnd index, -1 by default (-1: send list to end). Else a valid index of the list
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_WRITE_PARTIAL_LIST ( #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!

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
start_indexint16_tStart index, 0 by default and smaller / equal to the largest index of the current onboard list.
end_indexint16_tEnd index, equal or greater than start index.
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_ITEM ( #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). See also https://mavlink.io/en/protocol/mission.html.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence
frameuint8_tMAV_FRAMEThe coordinate system of the waypoint.
commanduint16_tMAV_CMDThe scheduled action for the waypoint.
currentuint8_tfalse:0, true:1
autocontinueuint8_tAutocontinue to next waypoint
param1floatPARAM1, see MAV_CMD enum
param2floatPARAM2, see MAV_CMD enum
param3floatPARAM3, see MAV_CMD enum
param4floatPARAM4, see MAV_CMD enum
xfloatPARAM5 / local: X coordinate, global: latitude
yfloatPARAM6 / local: Y coordinate, global: longitude
zfloatPARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_REQUEST ( #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/protocol/mission.html

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_SET_CURRENT ( #41 )

Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence

MISSION_CURRENT ( #42 )

Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.

Field NameTypeDescription
sequint16_tSequence

MISSION_REQUEST_LIST ( #43 )

Request the overall list of mission items from the system/component.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_COUNT ( #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.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
countuint16_tNumber of mission items in the sequence
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_CLEAR_ALL ( #45 )

Delete all mission items at once.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
mission_type **uint8_tMAV_MISSION_TYPEMission type.

MISSION_ITEM_REACHED ( #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.

Field NameTypeDescription
sequint16_tSequence

MISSION_ACK ( #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).

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
typeuint8_tMAV_MISSION_RESULTMission result.
mission_type **uint8_tMAV_MISSION_TYPEMission type.

SET_GPS_GLOBAL_ORIGIN ( #48 )

As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID
latitudeint32_tdegE7Latitude (WGS84)
longitudeint32_tdegE7Longitude (WGS84)
altitudeint32_tmmAltitude (MSL). Positive for up.
time_usec **uint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.

GPS_GLOBAL_ORIGIN ( #49 )

Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position

Field NameTypeUnitsDescription
latitudeint32_tdegE7Latitude (WGS84)
longitudeint32_tdegE7Longitude (WGS84)
altitudeint32_tmmAltitude (MSL). Positive for up.
time_usec **uint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.

PARAM_MAP_RC ( #50 )

Bind a RC channel to a parameter. The parameter should change according to the RC channel value.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
param_idchar[16]Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexint16_tParameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
parameter_rc_channel_indexuint8_tIndex of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC.
param_value0floatInitial parameter value
scalefloatScale, maps the RC range [-1, 1] to a parameter value
param_value_minfloatMinimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
param_value_maxfloatMaximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)

MISSION_REQUEST_INT ( #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/protocol/mission.html

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence
mission_type **uint8_tMAV_MISSION_TYPEMission type.

SAFETY_SET_ALLOWED_AREA ( #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.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
frameuint8_tMAV_FRAMECoordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
p1xfloatmx position 1 / Latitude 1
p1yfloatmy position 1 / Longitude 1
p1zfloatmz position 1 / Altitude 1
p2xfloatmx position 2 / Latitude 2
p2yfloatmy position 2 / Longitude 2
p2zfloatmz position 2 / Altitude 2

SAFETY_ALLOWED_AREA ( #55 )

Read out the safety zone the MAV currently assumes.

Field NameTypeUnitsValuesDescription
frameuint8_tMAV_FRAMECoordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
p1xfloatmx position 1 / Latitude 1
p1yfloatmy position 1 / Longitude 1
p1zfloatmz position 1 / Altitude 1
p2xfloatmx position 2 / Latitude 2
p2yfloatmy position 2 / Longitude 2
p2zfloatmz position 2 / Altitude 2

ATTITUDE_QUATERNION_COV ( #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).

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
qfloat[4]Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
rollspeedfloatrad/sRoll angular speed
pitchspeedfloatrad/sPitch angular speed
yawspeedfloatrad/sYaw angular speed
covariancefloat[9]Attitude covariance

The state of the fixed wing navigation and position controller.

Field NameTypeUnitsDescription
nav_rollfloatdegCurrent desired roll
nav_pitchfloatdegCurrent desired pitch
nav_bearingint16_tdegCurrent desired heading
target_bearingint16_tdegBearing to current waypoint/target
wp_distuint16_tmDistance to active waypoint
alt_errorfloatmCurrent altitude error
aspd_errorfloatm/sCurrent airspeed error
xtrack_errorfloatmCurrent crosstrack error on x-y plane

GLOBAL_POSITION_INT_COV ( #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.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
estimator_typeuint8_tMAV_ESTIMATOR_TYPEClass id of the estimator this estimate originated from.
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
altint32_tmmAltitude in meters above MSL
relative_altint32_tmmAltitude above ground
vxfloatm/sGround X Speed (Latitude)
vyfloatm/sGround Y Speed (Longitude)
vzfloatm/sGround Z Speed (Altitude)
covariancefloat[36]Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)

LOCAL_POSITION_NED_COV ( #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)

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
estimator_typeuint8_tMAV_ESTIMATOR_TYPEClass id of the estimator this estimate originated from.
xfloatmX Position
yfloatmY Position
zfloatmZ Position
vxfloatm/sX Speed
vyfloatm/sY Speed
vzfloatm/sZ Speed
axfloatm/s/sX Acceleration
ayfloatm/s/sY Acceleration
azfloatm/s/sZ Acceleration
covariancefloat[45]Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)

RC_CHANNELS ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
chancountuint8_tTotal number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
chan1_rawuint16_tusRC channel 1 value.
chan2_rawuint16_tusRC channel 2 value.
chan3_rawuint16_tusRC channel 3 value.
chan4_rawuint16_tusRC channel 4 value.
chan5_rawuint16_tusRC channel 5 value.
chan6_rawuint16_tusRC channel 6 value.
chan7_rawuint16_tusRC channel 7 value.
chan8_rawuint16_tusRC channel 8 value.
chan9_rawuint16_tusRC channel 9 value.
chan10_rawuint16_tusRC channel 10 value.
chan11_rawuint16_tusRC channel 11 value.
chan12_rawuint16_tusRC channel 12 value.
chan13_rawuint16_tusRC channel 13 value.
chan14_rawuint16_tusRC channel 14 value.
chan15_rawuint16_tusRC channel 15 value.
chan16_rawuint16_tusRC channel 16 value.
chan17_rawuint16_tusRC channel 17 value.
chan18_rawuint16_tusRC channel 18 value.
rssiuint8_t%Receive signal strength indicator. Values: [0-100], 255: invalid/unknown.

REQUEST_DATA_STREAM ( #66 )

DEPRECATED: Replaced by SET_MESSAGE_INTERVAL (2015-08).

Request a data stream.

Field NameTypeUnitsDescription
target_systemuint8_tThe target requested to send the message stream.
target_componentuint8_tThe target requested to send the message stream.
req_stream_iduint8_tThe ID of the requested data stream
req_message_rateuint16_tHzThe requested message rate
start_stopuint8_t1 to start sending, 0 to stop sending.

DATA_STREAM ( #67 )

DEPRECATED: Replaced by MESSAGE_INTERVAL (2015-08).

Data stream status information.

Field NameTypeUnitsDescription
stream_iduint8_tThe ID of the requested data stream
message_rateuint16_tHzThe message rate
on_offuint8_t1 stream is enabled, 0 stream is stopped.

MANUAL_CONTROL ( #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 an buttons are also transmit as boolean values of their

Field NameTypeDescription
targetuint8_tThe system to be controlled.
xint16_tX-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
yint16_tY-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
zint16_tZ-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
rint16_tR-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
buttonsuint16_tA bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.

RC_CHANNELS_OVERRIDE ( #70 )

The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
chan1_rawuint16_tusRC channel 1 value. A value of UINT16_MAX means to ignore this field.
chan2_rawuint16_tusRC channel 2 value. A value of UINT16_MAX means to ignore this field.
chan3_rawuint16_tusRC channel 3 value. A value of UINT16_MAX means to ignore this field.
chan4_rawuint16_tusRC channel 4 value. A value of UINT16_MAX means to ignore this field.
chan5_rawuint16_tusRC channel 5 value. A value of UINT16_MAX means to ignore this field.
chan6_rawuint16_tusRC channel 6 value. A value of UINT16_MAX means to ignore this field.
chan7_rawuint16_tusRC channel 7 value. A value of UINT16_MAX means to ignore this field.
chan8_rawuint16_tusRC channel 8 value. A value of UINT16_MAX means to ignore this field.
chan9_raw **uint16_tusRC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field.
chan10_raw **uint16_tusRC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field.
chan11_raw **uint16_tusRC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field.
chan12_raw **uint16_tusRC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field.
chan13_raw **uint16_tusRC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field.
chan14_raw **uint16_tusRC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field.
chan15_raw **uint16_tusRC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field.
chan16_raw **uint16_tusRC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field.
chan17_raw **uint16_tusRC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field.
chan18_raw **uint16_tusRC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field.

MISSION_ITEM_INT ( #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). See also https://mavlink.io/en/protocol/mission.html.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tWaypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
frameuint8_tMAV_FRAMEThe coordinate system of the waypoint.
commanduint16_tMAV_CMDThe scheduled action for the waypoint.
currentuint8_tfalse:0, true:1
autocontinueuint8_tAutocontinue to next waypoint
param1floatPARAM1, see MAV_CMD enum
param2floatPARAM2, see MAV_CMD enum
param3floatPARAM3, see MAV_CMD enum
param4floatPARAM4, see MAV_CMD enum
xint32_tPARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
yint32_tPARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
zfloatPARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
mission_type **uint8_tMAV_MISSION_TYPEMission type.

VFR_HUD ( #74 )

Metrics typically displayed on a HUD for fixed wing aircraft

Field NameTypeUnitsDescription
airspeedfloatm/sCurrent airspeed
groundspeedfloatm/sCurrent ground speed
headingint16_tdegCurrent heading in degrees, in compass units (0..360, 0=north)
throttleuint16_t%Current throttle setting in integer percent, 0 to 100
altfloatmCurrent altitude (MSL)
climbfloatm/sCurrent climb rate

COMMAND_INT ( #75 )

Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
frameuint8_tMAV_FRAMEThe coordinate system of the COMMAND.
commanduint16_tMAV_CMDThe scheduled action for the mission item.
currentuint8_tfalse:0, true:1
autocontinueuint8_tautocontinue to next wp
param1floatPARAM1, see MAV_CMD enum
param2floatPARAM2, see MAV_CMD enum
param3floatPARAM3, see MAV_CMD enum
param4floatPARAM4, see MAV_CMD enum
xint32_tPARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
yint32_tPARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
zfloatPARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).

COMMAND_LONG ( #76 )

Send a command with up to seven parameters to the MAV

Field NameTypeValuesDescription
target_systemuint8_tSystem which should execute the command
target_componentuint8_tComponent which should execute the command, 0 for all components
commanduint16_tMAV_CMDCommand ID (of command to send).
confirmationuint8_t0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
param1floatParameter 1 (for the specific command).
param2floatParameter 2 (for the specific command).
param3floatParameter 3 (for the specific command).
param4floatParameter 4 (for the specific command).
param5floatParameter 5 (for the specific command).
param6floatParameter 6 (for the specific command).
param7floatParameter 7 (for the specific command).

COMMAND_ACK ( #77 )

Report status of a command. Includes feedback whether the command was executed.

Field NameTypeValuesDescription
commanduint16_tMAV_CMDCommand ID (of acknowledged command).
resultuint8_tMAV_RESULTResult of command.
progress **uint8_tWIP: Also used as result_param1, it can be set with a enum containing the errors reasons of why the command was denied or the progress percentage or 255 if unknown the progress when result is MAV_RESULT_IN_PROGRESS.
result_param2 **int32_tWIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
target_system **uint8_tWIP: System which requested the command to be executed
target_component **uint8_tWIP: Component which requested the command to be executed

MANUAL_SETPOINT ( #81 )

Setpoint in roll, pitch, yaw and thrust from the operator

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
rollfloatrad/sDesired roll rate
pitchfloatrad/sDesired pitch rate
yawfloatrad/sDesired yaw rate
thrustfloatCollective thrust, normalized to 0 .. 1
mode_switchuint8_tFlight mode switch position, 0.. 255
manual_override_switchuint8_tOverride mode switch position, 0.. 255

SET_ATTITUDE_TARGET ( #82 )

Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system).

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
type_maskuint8_tMappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
qfloat[4]Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
body_roll_ratefloatrad/sBody roll rate
body_pitch_ratefloatrad/sBody pitch rate
body_yaw_ratefloatrad/sBody yaw rate
thrustfloatCollective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)

ATTITUDE_TARGET ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
type_maskuint8_tMappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
qfloat[4]Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
body_roll_ratefloatrad/sBody roll rate
body_pitch_ratefloatrad/sBody pitch rate
body_yaw_ratefloatrad/sBody yaw rate
thrustfloatCollective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)

SET_POSITION_TARGET_LOCAL_NED ( #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).

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
coordinate_frameuint8_tMAV_FRAMEValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
type_maskuint16_tPOSITION_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
xfloatmX Position in NED frame
yfloatmY Position in NED frame
zfloatmZ Position in NED frame (note, altitude is negative in NED)
vxfloatm/sX velocity in NED frame
vyfloatm/sY velocity in NED frame
vzfloatm/sZ velocity in NED frame
afxfloatm/s/sX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyfloatm/s/sY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzfloatm/s/sZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawfloatradyaw setpoint
yaw_ratefloatrad/syaw rate setpoint

POSITION_TARGET_LOCAL_NED ( #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.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
coordinate_frameuint8_tMAV_FRAMEValid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
type_maskuint16_tPOSITION_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
xfloatmX Position in NED frame
yfloatmY Position in NED frame
zfloatmZ Position in NED frame (note, altitude is negative in NED)
vxfloatm/sX velocity in NED frame
vyfloatm/sY velocity in NED frame
vzfloatm/sZ velocity in NED frame
afxfloatm/s/sX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyfloatm/s/sY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzfloatm/s/sZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawfloatradyaw setpoint
yaw_ratefloatrad/syaw rate setpoint

SET_POSITION_TARGET_GLOBAL_INT ( #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).

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
coordinate_frameuint8_tMAV_FRAMEValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
type_maskuint16_tPOSITION_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
lat_intint32_tdegE7X Position in WGS84 frame
lon_intint32_tdegE7Y Position in WGS84 frame
altfloatmAltitude (MSL, Relative to home, or AGL - depending on frame)
vxfloatm/sX velocity in NED frame
vyfloatm/sY velocity in NED frame
vzfloatm/sZ velocity in NED frame
afxfloatm/s/sX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyfloatm/s/sY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzfloatm/s/sZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawfloatradyaw setpoint
yaw_ratefloatrad/syaw rate setpoint

POSITION_TARGET_GLOBAL_INT ( #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.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
coordinate_frameuint8_tMAV_FRAMEValid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
type_maskuint16_tPOSITION_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
lat_intint32_tdegE7X Position in WGS84 frame
lon_intint32_tdegE7Y Position in WGS84 frame
altfloatmAltitude (MSL, AGL or relative to home altitude, depending on frame)
vxfloatm/sX velocity in NED frame
vyfloatm/sY velocity in NED frame
vzfloatm/sZ velocity in NED frame
afxfloatm/s/sX acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afyfloatm/s/sY acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
afzfloatm/s/sZ acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
yawfloatradyaw setpoint
yaw_ratefloatrad/syaw rate setpoint

LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET ( #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)

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
xfloatmX Position
yfloatmY Position
zfloatmZ Position
rollfloatradRoll
pitchfloatradPitch
yawfloatradYaw

HIL_STATE ( #90 )

DEPRECATED: Replaced by HIL_STATE_QUATERNION (2013-07). Suffers from missing airspeed fields and singularities due to Euler angles

Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
rollfloatradRoll angle
pitchfloatradPitch angle
yawfloatradYaw angle
rollspeedfloatrad/sBody frame roll / phi angular speed
pitchspeedfloatrad/sBody frame pitch / theta angular speed
yawspeedfloatrad/sBody frame yaw / psi angular speed
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
altint32_tmmAltitude
vxint16_tcm/sGround X Speed (Latitude)
vyint16_tcm/sGround Y Speed (Longitude)
vzint16_tcm/sGround Z Speed (Altitude)
xaccint16_tmGX acceleration
yaccint16_tmGY acceleration
zaccint16_tmGZ acceleration

HIL_CONTROLS ( #91 )

Sent from autopilot to simulation. Hardware in the loop control outputs

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
roll_aileronsfloatControl output -1 .. 1
pitch_elevatorfloatControl output -1 .. 1
yaw_rudderfloatControl output -1 .. 1
throttlefloatThrottle 0 .. 1
aux1floatAux 1, -1 .. 1
aux2floatAux 2, -1 .. 1
aux3floatAux 3, -1 .. 1
aux4floatAux 4, -1 .. 1
modeuint8_tMAV_MODESystem mode.
nav_modeuint8_tNavigation mode (MAV_NAV_MODE)

HIL_RC_INPUTS_RAW ( #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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
chan1_rawuint16_tusRC channel 1 value
chan2_rawuint16_tusRC channel 2 value
chan3_rawuint16_tusRC channel 3 value
chan4_rawuint16_tusRC channel 4 value
chan5_rawuint16_tusRC channel 5 value
chan6_rawuint16_tusRC channel 6 value
chan7_rawuint16_tusRC channel 7 value
chan8_rawuint16_tusRC channel 8 value
chan9_rawuint16_tusRC channel 9 value
chan10_rawuint16_tusRC channel 10 value
chan11_rawuint16_tusRC channel 11 value
chan12_rawuint16_tusRC channel 12 value
rssiuint8_tReceive signal strength indicator. Values: [0-100], 255: invalid/unknown.

HIL_ACTUATOR_CONTROLS ( #93 )

Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
controlsfloat[16]Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
modeuint8_tMAV_MODESystem mode. Includes arming state.
flagsuint64_tFlags as bitfield, reserved for future use.

OPTICAL_FLOW ( #100 )

Optical flow from a flow sensor (e.g. optical mouse sensor)

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
sensor_iduint8_tSensor ID
flow_xint16_tdpixFlow in x-sensor direction
flow_yint16_tdpixFlow in y-sensor direction
flow_comp_m_xfloatmFlow in x-sensor direction, angular-speed compensated
flow_comp_m_yfloatmFlow in y-sensor direction, angular-speed compensated
qualityuint8_tOptical flow quality / confidence. 0: bad, 255: maximum quality
ground_distancefloatmGround distance. Positive value: distance known. Negative value: Unknown distance
flow_rate_x **floatrad/sFlow rate about X axis
flow_rate_y **floatrad/sFlow rate about Y axis

GLOBAL_VISION_POSITION_ESTIMATE ( #101 )

Global position/attitude estimate from a vision source.

Field NameTypeUnitsDescription
usecuint64_tusTimestamp (UNIX time or since system boot)
xfloatmGlobal X position
yfloatmGlobal Y position
zfloatmGlobal Z position
rollfloatradRoll angle
pitchfloatradPitch angle
yawfloatradYaw angle
covariance **float[21]Pose covariance matrix upper right triangular (first six entries are the first ROW, next five entries are the second ROW, etc.)

VISION_POSITION_ESTIMATE ( #102 )

Global position/attitude estimate from a vision source.

Field NameTypeUnitsDescription
usecuint64_tusTimestamp (UNIX time or time since system boot)
xfloatmGlobal X position
yfloatmGlobal Y position
zfloatmGlobal Z position
rollfloatradRoll angle
pitchfloatradPitch angle
yawfloatradYaw angle
covariance **float[21]Pose covariance matrix upper right triangular (first six entries are the first ROW, next five entries are the second ROW, etc.)

VISION_SPEED_ESTIMATE ( #103 )

Speed estimate from a vision source.

Field NameTypeUnitsDescription
usecuint64_tusTimestamp (UNIX time or time since system boot)
xfloatm/sGlobal X speed
yfloatm/sGlobal Y speed
zfloatm/sGlobal Z speed
covariance **float[9]Linear velocity covariance matrix (1st three entries - 1st row, etc.)

VICON_POSITION_ESTIMATE ( #104 )

Global position estimate from a Vicon motion system source.

Field NameTypeUnitsDescription
usecuint64_tusTimestamp (UNIX time or time since system boot)
xfloatmGlobal X position
yfloatmGlobal Y position
zfloatmGlobal Z position
rollfloatradRoll angle
pitchfloatradPitch angle
yawfloatradYaw angle
covariance **float[21]Pose covariance matrix upper right triangular (first six entries are the first ROW, next five entries are the second ROW, etc.)

HIGHRES_IMU ( #105 )

The IMU readings in SI units in NED body frame

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
xaccfloatm/s/sX acceleration
yaccfloatm/s/sY acceleration
zaccfloatm/s/sZ acceleration
xgyrofloatrad/sAngular speed around X axis
ygyrofloatrad/sAngular speed around Y axis
zgyrofloatrad/sAngular speed around Z axis
xmagfloatgaussX Magnetic field
ymagfloatgaussY Magnetic field
zmagfloatgaussZ Magnetic field
abs_pressurefloatmbarAbsolute pressure
diff_pressurefloatmbarDifferential pressure
pressure_altfloatAltitude calculated from pressure
temperaturefloatdegCTemperature
fields_updateduint16_tBitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature

OPTICAL_FLOW_RAD ( #106 )

Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
sensor_iduint8_tSensor ID
integration_time_usuint32_tusIntegration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_xfloatradFlow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_yfloatradFlow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyrofloatradRH rotation around X axis
integrated_ygyrofloatradRH rotation around Y axis
integrated_zgyrofloatradRH rotation around Z axis
temperatureint16_tcdegCTemperature
qualityuint8_tOptical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_usuint32_tusTime since the distance was sampled.
distancefloatmDistance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.

HIL_SENSOR ( #107 )

The IMU readings in SI units in NED body frame

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
xaccfloatm/s/sX acceleration
yaccfloatm/s/sY acceleration
zaccfloatm/s/sZ acceleration
xgyrofloatrad/sAngular speed around X axis in body frame
ygyrofloatrad/sAngular speed around Y axis in body frame
zgyrofloatrad/sAngular speed around Z axis in body frame
xmagfloatgaussX Magnetic field
ymagfloatgaussY Magnetic field
zmagfloatgaussZ Magnetic field
abs_pressurefloatmbarAbsolute pressure
diff_pressurefloatmbarDifferential pressure (airspeed)
pressure_altfloatAltitude calculated from pressure
temperaturefloatdegCTemperature
fields_updateduint32_tBitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.

SIM_STATE ( #108 )

Status of simulation environment, if used

Field NameTypeUnitsDescription
q1floatTrue attitude quaternion component 1, w (1 in null-rotation)
q2floatTrue attitude quaternion component 2, x (0 in null-rotation)
q3floatTrue attitude quaternion component 3, y (0 in null-rotation)
q4floatTrue attitude quaternion component 4, z (0 in null-rotation)
rollfloatAttitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitchfloatAttitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yawfloatAttitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xaccfloatm/s/sX acceleration
yaccfloatm/s/sY acceleration
zaccfloatm/s/sZ acceleration
xgyrofloatrad/sAngular speed around X axis
ygyrofloatrad/sAngular speed around Y axis
zgyrofloatrad/sAngular speed around Z axis
latfloatdegLatitude
lonfloatdegLongitude
altfloatmAltitude
std_dev_horzfloatHorizontal position standard deviation
std_dev_vertfloatVertical position standard deviation
vnfloatm/sTrue velocity in NORTH direction in earth-fixed NED frame
vefloatm/sTrue velocity in EAST direction in earth-fixed NED frame
vdfloatm/sTrue velocity in DOWN direction in earth-fixed NED frame

RADIO_STATUS ( #109 )

Status generated by radio and injected into MAVLink stream.

Field NameTypeUnitsDescription
rssiuint8_tLocal signal strength
remrssiuint8_tRemote signal strength
txbufuint8_t%Remaining free buffer space.
noiseuint8_tBackground noise level
remnoiseuint8_tRemote background noise level
rxerrorsuint16_tReceive errors
fixeduint16_tCount of error corrected packets

FILE_TRANSFER_PROTOCOL ( #110 )

File transfer message

Field NameTypeDescription
target_networkuint8_tNetwork ID (0 for broadcast)
target_systemuint8_tSystem ID (0 for broadcast)
target_componentuint8_tComponent ID (0 for broadcast)
payloaduint8_t[251]Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.

TIMESYNC ( #111 )

Time synchronization message.

Field NameTypeDescription
tc1int64_tTime sync timestamp 1
ts1int64_tTime sync timestamp 2

CAMERA_TRIGGER ( #112 )

Camera-IMU triggering and synchronisation message.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp for image frame (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 the number.
sequint32_tImage frame sequence

HIL_GPS ( #113 )

The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
fix_typeuint8_t0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altint32_tmmAltitude (MSL). Positive for up.
ephuint16_tcmGPS HDOP horizontal dilution of position. If unknown, set to: 65535
epvuint16_tcmGPS VDOP vertical dilution of position. If unknown, set to: 65535
veluint16_tcm/sGPS ground speed. If unknown, set to: 65535
vnint16_tcm/sGPS velocity in NORTH direction in earth-fixed NED frame
veint16_tcm/sGPS velocity in EAST direction in earth-fixed NED frame
vdint16_tcm/sGPS velocity in DOWN direction in earth-fixed NED frame
coguint16_tcdegCourse over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
satellites_visibleuint8_tNumber of satellites visible. If unknown, set to 255

HIL_OPTICAL_FLOW ( #114 )

Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
sensor_iduint8_tSensor ID
integration_time_usuint32_tusIntegration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
integrated_xfloatradFlow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
integrated_yfloatradFlow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
integrated_xgyrofloatradRH rotation around X axis
integrated_ygyrofloatradRH rotation around Y axis
integrated_zgyrofloatradRH rotation around Z axis
temperatureint16_tcdegCTemperature
qualityuint8_tOptical flow quality / confidence. 0: no valid flow, 255: maximum quality
time_delta_distance_usuint32_tusTime since the distance was sampled.
distancefloatmDistance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.

HIL_STATE_QUATERNION ( #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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
attitude_quaternionfloat[4]Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
rollspeedfloatrad/sBody frame roll / phi angular speed
pitchspeedfloatrad/sBody frame pitch / theta angular speed
yawspeedfloatrad/sBody frame yaw / psi angular speed
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
altint32_tmmAltitude
vxint16_tcm/sGround X Speed (Latitude)
vyint16_tcm/sGround Y Speed (Longitude)
vzint16_tcm/sGround Z Speed (Altitude)
ind_airspeeduint16_tcm/sIndicated airspeed
true_airspeeduint16_tcm/sTrue airspeed
xaccint16_tmGX acceleration
yaccint16_tmGY acceleration
zaccint16_tmGZ acceleration

SCALED_IMU2 ( #116 )

The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
xaccint16_tmGX acceleration
yaccint16_tmGY acceleration
zaccint16_tmGZ acceleration
xgyroint16_tmrad/sAngular speed around X axis
ygyroint16_tmrad/sAngular speed around Y axis
zgyroint16_tmrad/sAngular speed around Z axis
xmagint16_tmTX Magnetic field
ymagint16_tmTY Magnetic field
zmagint16_tmTZ Magnetic field

LOG_REQUEST_LIST ( #117 )

Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
startuint16_tFirst log id (0 for first available)
enduint16_tLast log id (0xffff for last available)

LOG_ENTRY ( #118 )

Reply to LOG_REQUEST_LIST

Field NameTypeUnitsDescription
iduint16_tLog id
num_logsuint16_tTotal number of logs
last_log_numuint16_tHigh log number
time_utcuint32_tsUTC timestamp of log since 1970, or 0 if not available
sizeuint32_tbytesSize of the log (may be approximate)

LOG_REQUEST_DATA ( #119 )

Request a chunk of a log

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
iduint16_tLog id (from LOG_ENTRY reply)
ofsuint32_tOffset into the log
countuint32_tbytesNumber of bytes

LOG_DATA ( #120 )

Reply to LOG_REQUEST_DATA

Field NameTypeUnitsDescription
iduint16_tLog id (from LOG_ENTRY reply)
ofsuint32_tOffset into the log
countuint8_tbytesNumber of bytes (zero for end of log)
datauint8_t[90]log data

LOG_ERASE ( #121 )

Erase all logs

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

LOG_REQUEST_END ( #122 )

Stop log transfer and resume normal logging

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

GPS_INJECT_DATA ( #123 )

Data for injecting into the onboard GPS (used for DGPS)

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
lenuint8_tbytesData length
datauint8_t[110]Raw data (110 is enough for 12 satellites of RTCMv2)

GPS2_RAW ( #124 )

Second GPS data.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
fix_typeuint8_tGPS_FIX_TYPEGPS fix type.
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altint32_tmmAltitude (MSL). Positive for up.
ephuint16_tcmGPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
epvuint16_tcmGPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
veluint16_tcm/sGPS ground speed. If unknown, set to: UINT16_MAX
coguint16_tcdegCourse over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
satellites_visibleuint8_tNumber of satellites visible. If unknown, set to 255
dgps_numchuint8_tNumber of DGPS satellites
dgps_ageuint32_tmsAge of DGPS info

POWER_STATUS ( #125 )

Power supply status

Field NameTypeUnitsValuesDescription
Vccuint16_tmV5V rail voltage.
Vservouint16_tmVServo rail voltage.
flagsuint16_tMAV_POWER_STATUSBitmap of power supply status flags.

SERIAL_CONTROL ( #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.

Field NameTypeUnitsValuesDescription
deviceuint8_tSERIAL_CONTROL_DEVSerial control device type.
flagsuint8_tSERIAL_CONTROL_FLAGBitmap of serial control flags.
timeoutuint16_tmsTimeout for reply data
baudrateuint32_tbits/sBaudrate of transfer. Zero means no change.
countuint8_tbyteshow many bytes in this transfer
datauint8_t[70]serial data

GPS_RTK ( #127 )

RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

Field NameTypeUnitsValuesDescription
time_last_baseline_msuint32_tmsTime since boot of last baseline message received.
rtk_receiver_iduint8_tIdentification of connected RTK receiver.
wnuint16_tGPS Week Number of last baseline
towuint32_tmsGPS Time of Week of last baseline
rtk_healthuint8_tGPS-specific health report for RTK data.
rtk_rateuint8_tHzRate of baseline messages being received by GPS
nsatsuint8_tCurrent number of sats used for RTK calculation.
baseline_coords_typeuint8_tRTK_BASELINE_COORDINATE_SYSTEMCoordinate system of baseline
baseline_a_mmint32_tmmCurrent baseline in ECEF x or NED north component.
baseline_b_mmint32_tmmCurrent baseline in ECEF y or NED east component.
baseline_c_mmint32_tmmCurrent baseline in ECEF z or NED down component.
accuracyuint32_tCurrent estimate of baseline accuracy.
iar_num_hypothesesint32_tCurrent number of integer ambiguity hypotheses.

GPS2_RTK ( #128 )

RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting

Field NameTypeUnitsValuesDescription
time_last_baseline_msuint32_tmsTime since boot of last baseline message received.
rtk_receiver_iduint8_tIdentification of connected RTK receiver.
wnuint16_tGPS Week Number of last baseline
towuint32_tmsGPS Time of Week of last baseline
rtk_healthuint8_tGPS-specific health report for RTK data.
rtk_rateuint8_tHzRate of baseline messages being received by GPS
nsatsuint8_tCurrent number of sats used for RTK calculation.
baseline_coords_typeuint8_tRTK_BASELINE_COORDINATE_SYSTEMCoordinate system of baseline
baseline_a_mmint32_tmmCurrent baseline in ECEF x or NED north component.
baseline_b_mmint32_tmmCurrent baseline in ECEF y or NED east component.
baseline_c_mmint32_tmmCurrent baseline in ECEF z or NED down component.
accuracyuint32_tCurrent estimate of baseline accuracy.
iar_num_hypothesesint32_tCurrent number of integer ambiguity hypotheses.

SCALED_IMU3 ( #129 )

The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
xaccint16_tmGX acceleration
yaccint16_tmGY acceleration
zaccint16_tmGZ acceleration
xgyroint16_tmrad/sAngular speed around X axis
ygyroint16_tmrad/sAngular speed around Y axis
zgyroint16_tmrad/sAngular speed around Z axis
xmagint16_tmTX Magnetic field
ymagint16_tmTY Magnetic field
zmagint16_tmTZ Magnetic field

DATA_TRANSMISSION_HANDSHAKE ( #130 )

Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/protocol/image_transmission.html.

Field NameTypeUnitsValuesDescription
typeuint8_tDATA_TYPESType of requested/acknowledged data.
sizeuint32_tbytestotal data size (set on ACK only).
widthuint16_tWidth of a matrix or image.
heightuint16_tHeight of a matrix or image.
packetsuint16_tNumber of packets being sent (set on ACK only).
payloaduint8_tbytesPayload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only).
jpg_qualityuint8_t%JPEG quality. Values: [1-100].

ENCAPSULATED_DATA ( #131 )

Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/protocol/image_transmission.html.

Field NameTypeDescription
seqnruint16_tsequence number (starting with 0 on every transmission)
datauint8_t[253]image data bytes

DISTANCE_SENSOR ( #132 )

Distance sensor information for an onboard rangefinder.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
min_distanceuint16_tcmMinimum distance the sensor can measure
max_distanceuint16_tcmMaximum distance the sensor can measure
current_distanceuint16_tcmCurrent distance reading
typeuint8_tMAV_DISTANCE_SENSORType of distance sensor.
iduint8_tOnboard ID of the sensor
orientationuint8_tMAV_SENSOR_ORIENTATIONDirection the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
covarianceuint8_tcmMeasurement covariance, 0 for unknown / invalid readings

TERRAIN_REQUEST ( #133 )

Request for terrain data and terrain status

Field NameTypeUnitsDescription
latint32_tdegE7Latitude of SW corner of first grid
lonint32_tdegE7Longitude of SW corner of first grid
grid_spacinguint16_tmGrid spacing
maskuint64_tBitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)

TERRAIN_DATA ( #134 )

Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST

Field NameTypeUnitsDescription
latint32_tdegE7Latitude of SW corner of first grid
lonint32_tdegE7Longitude of SW corner of first grid
grid_spacinguint16_tmGrid spacing
gridbituint8_tbit within the terrain request mask
dataint16_t[16]mTerrain data MSL

TERRAIN_CHECK ( #135 )

Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission.

Field NameTypeUnitsDescription
latint32_tdegE7Latitude
lonint32_tdegE7Longitude

TERRAIN_REPORT ( #136 )

Response from a TERRAIN_CHECK request

Field NameTypeUnitsDescription
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
spacinguint16_tgrid spacing (zero if terrain at this location unavailable)
terrain_heightfloatmTerrain height MSL
current_heightfloatmCurrent vehicle height above lat/lon terrain height
pendinguint16_tNumber of 4x4 terrain blocks waiting to be received or read from disk
loadeduint16_tNumber of 4x4 terrain blocks in memory

SCALED_PRESSURE2 ( #137 )

Barometer readings for 2nd barometer

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
press_absfloathPaAbsolute pressure
press_difffloathPaDifferential pressure
temperatureint16_tcdegCTemperature measurement

ATT_POS_MOCAP ( #138 )

Motion capture attitude and position

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
qfloat[4]Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
xfloatmX position (NED)
yfloatmY position (NED)
zfloatmZ position (NED)
covariance **float[21]Pose covariance matrix upper right triangular (first six entries are the first ROW, next five entries are the second ROW, etc.)

SET_ACTUATOR_CONTROL_TARGET ( #139 )

Set the vehicle attitude and body angular rates.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
group_mlxuint8_tActuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
controlsfloat[8]Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.

ACTUATOR_CONTROL_TARGET ( #140 )

Set the vehicle attitude and body angular rates.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
group_mlxuint8_tActuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
controlsfloat[8]Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.

ALTITUDE ( #141 )

The current system altitude.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
altitude_monotonicfloatmThis altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
altitude_amslfloatmThis altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
altitude_localfloatmThis is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
altitude_relativefloatmThis is the altitude above the home position. It resets on each change of the current home position.
altitude_terrainfloatmThis is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
bottom_clearancefloatmThis is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.

RESOURCE_REQUEST ( #142 )

The autopilot is requesting a resource (file, binary, other type of data)

Field NameTypeDescription
request_iduint8_tRequest ID. This ID should be re-used when sending back URI contents
uri_typeuint8_tThe type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary
uriuint8_t[120]The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)
transfer_typeuint8_tThe way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.
storageuint8_t[120]The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).

SCALED_PRESSURE3 ( #143 )

Barometer readings for 3rd barometer

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
press_absfloathPaAbsolute pressure
press_difffloathPaDifferential pressure
temperatureint16_tcdegCTemperature measurement

FOLLOW_TARGET ( #144 )

Current motion information from a designated system

Field NameTypeUnitsDescription
timestampuint64_tmsTimestamp (time since system boot).
est_capabilitiesuint8_tbit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altfloatmAltitude (MSL)
velfloat[3]m/starget velocity (0,0,0) for unknown
accfloat[3]m/s/slinear target acceleration (0,0,0) for unknown
attitude_qfloat[4](1 0 0 0 for unknown)
ratesfloat[3](0 0 0 for unknown)
position_covfloat[3]eph epv
custom_stateuint64_tbutton states or switches of a tracker device

CONTROL_SYSTEM_STATE ( #146 )

The smoothed, monotonic system state used to feed the control loops of the system.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
x_accfloatm/s/sX acceleration in body frame
y_accfloatm/s/sY acceleration in body frame
z_accfloatm/s/sZ acceleration in body frame
x_velfloatm/sX velocity in body frame
y_velfloatm/sY velocity in body frame
z_velfloatm/sZ velocity in body frame
x_posfloatmX position in local frame
y_posfloatmY position in local frame
z_posfloatmZ position in local frame
airspeedfloatm/sAirspeed, set to -1 if unknown
vel_variancefloat[3]Variance of body velocity estimate
pos_variancefloat[3]Variance in local position
qfloat[4]The attitude, represented as Quaternion
roll_ratefloatrad/sAngular rate in roll axis
pitch_ratefloatrad/sAngular rate in pitch axis
yaw_ratefloatrad/sAngular rate in yaw axis

BATTERY_STATUS ( #147 )

Battery information

Field NameTypeUnitsValuesDescription
iduint8_tBattery ID
battery_functionuint8_tMAV_BATTERY_FUNCTIONFunction of the battery
typeuint8_tMAV_BATTERY_TYPEType (chemistry) of the battery
temperatureint16_tcdegCTemperature of the battery. INT16_MAX for unknown temperature.
voltagesuint16_t[10]mVBattery voltage of cells. Cells above the valid cell count for this battery should have the UINT16_MAX value.
current_batteryint16_tcABattery current, -1: autopilot does not measure the current
current_consumedint32_tmAhConsumed charge, -1: autopilot does not provide consumption estimate
energy_consumedint32_thJConsumed energy, -1: autopilot does not provide energy consumption estimate
battery_remainingint8_t%Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
time_remaining **int32_tsRemaining battery time, 0: autopilot does not provide remaining battery time estimate
charge_state **uint8_tMAV_BATTERY_CHARGE_STATEState for extent of discharge, provided by autopilot for warning or external reactions

AUTOPILOT_VERSION ( #148 )

Version and capability of autopilot software

Field NameTypeValuesDescription
capabilitiesuint64_tMAV_PROTOCOL_CAPABILITYBitmap of capabilities
flight_sw_versionuint32_tFirmware version number
middleware_sw_versionuint32_tMiddleware version number
os_sw_versionuint32_tOperating system version number
board_versionuint32_tHW / board version (last 8 bytes should be silicon ID, if any)
flight_custom_versionuint8_t[8]Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
middleware_custom_versionuint8_t[8]Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
os_custom_versionuint8_t[8]Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
vendor_iduint16_tID of the board vendor
product_iduint16_tID of the product
uiduint64_tUID if provided by hardware (see uid2)
uid2 **uint8_t[18]UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)

LANDING_TARGET ( #149 )

The location of a landing target. See: https://mavlink.io/en/protocol/landing_target.html

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
target_numuint8_tThe ID of the target if multiple targets are present
frameuint8_tMAV_FRAMECoordinate frame used for following fields.
angle_xfloatradX-axis angular offset of the target from the center of the image
angle_yfloatradY-axis angular offset of the target from the center of the image
distancefloatmDistance to the target from the vehicle
size_xfloatradSize of target along x-axis
size_yfloatradSize of target along y-axis
x **floatmX Position of the landing target in MAV_FRAME
y **floatmY Position of the landing target in MAV_FRAME
z **floatmZ Position of the landing target in MAV_FRAME
q **float[4]Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
type **uint8_tLANDING_TARGET_TYPEType of landing target
position_valid **uint8_tBoolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).

ESTIMATOR_STATUS ( #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.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
flagsuint16_tESTIMATOR_STATUS_FLAGSBitmap indicating which EKF outputs are valid.
vel_ratiofloatVelocity innovation test ratio
pos_horiz_ratiofloatHorizontal position innovation test ratio
pos_vert_ratiofloatVertical position innovation test ratio
mag_ratiofloatMagnetometer innovation test ratio
hagl_ratiofloatHeight above terrain innovation test ratio
tas_ratiofloatTrue airspeed innovation test ratio
pos_horiz_accuracyfloatmHorizontal position 1-STD accuracy relative to the EKF local origin
pos_vert_accuracyfloatmVertical position 1-STD accuracy relative to the EKF local origin

WIND_COV ( #231 )

Wind covariance estimate from vehicle.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
wind_xfloatm/sWind in X (NED) direction
wind_yfloatm/sWind in Y (NED) direction
wind_zfloatm/sWind in Z (NED) direction
var_horizfloatm/sVariability of the wind in XY. RMS of a 1 Hz lowpassed wind estimate.
var_vertfloatm/sVariability of the wind in Z. RMS of a 1 Hz lowpassed wind estimate.
wind_altfloatmAltitude (MSL) that this measurement was taken at
horiz_accuracyfloatmHorizontal speed 1-STD accuracy
vert_accuracyfloatmVertical speed 1-STD accuracy

GPS_INPUT ( #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.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
gps_iduint8_tID of the GPS for multiple GPS inputs
ignore_flagsuint16_tGPS_INPUT_IGNORE_FLAGSBitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
time_week_msuint32_tmsGPS time (from start of GPS week)
time_weekuint16_tGPS week number
fix_typeuint8_t0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altfloatmAltitude (MSL). Positive for up.
hdopfloatmGPS HDOP horizontal dilution of position
vdopfloatmGPS VDOP vertical dilution of position
vnfloatm/sGPS velocity in NORTH direction in earth-fixed NED frame
vefloatm/sGPS velocity in EAST direction in earth-fixed NED frame
vdfloatm/sGPS velocity in DOWN direction in earth-fixed NED frame
speed_accuracyfloatm/sGPS speed accuracy
horiz_accuracyfloatmGPS horizontal accuracy
vert_accuracyfloatmGPS vertical accuracy
satellites_visibleuint8_tNumber of satellites visible.

GPS_RTCM_DATA ( #233 )

RTCM message for injecting into the onboard GPS (used for DGPS)

Field NameTypeUnitsDescription
flagsuint8_tLSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order.
lenuint8_tbytesdata length
datauint8_t[180]RTCM message (may be fragmented)

HIGH_LATENCY ( #234 )

Message appropriate for high latency connections like Iridium

Field NameTypeUnitsValuesDescription
base_modeuint8_tMAV_MODE_FLAGBitmap of enabled system modes.
custom_modeuint32_tA bitfield for use for autopilot-specific flags.
landed_stateuint8_tMAV_LANDED_STATEThe landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
rollint16_tcdegroll
pitchint16_tcdegpitch
headinguint16_tcdegheading
throttleint8_t%throttle (percentage)
heading_spint16_tcdegheading setpoint
latitudeint32_tdegE7Latitude
longitudeint32_tdegE7Longitude
altitude_amslint16_tmAltitude above mean sea level
altitude_spint16_tmAltitude setpoint relative to the home position
airspeeduint8_tm/sairspeed
airspeed_spuint8_tm/sairspeed setpoint
groundspeeduint8_tm/sgroundspeed
climb_rateint8_tm/sclimb rate
gps_nsatuint8_tNumber of satellites visible. If unknown, set to 255
gps_fix_typeuint8_tGPS_FIX_TYPEGPS Fix type.
battery_remaininguint8_t%Remaining battery (percentage)
temperatureint8_tdegCAutopilot temperature (degrees C)
temperature_airint8_tdegCAir temperature (degrees C) from airspeed sensor
failsafeuint8_tfailsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)
wp_numuint8_tcurrent waypoint number
wp_distanceuint16_tmdistance to target

HIGH_LATENCY2 ( #235 )

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

Message appropriate for high latency connections like Iridium (version 2)

Field NameTypeUnitsValuesDescription
timestampuint32_tmsTimestamp (milliseconds since boot or Unix epoch)
typeuint8_tMAV_TYPEType of the MAV (quadrotor, helicopter, etc.)
autopilotuint8_tMAV_AUTOPILOTAutopilot type / class.
custom_modeuint16_tA bitfield for use for autopilot-specific flags (2 byte version).
latitudeint32_tdegE7Latitude
longitudeint32_tdegE7Longitude
altitudeint16_tmAltitude above mean sea level
target_altitudeint16_tmAltitude setpoint
headinguint8_tdeg/2Heading
target_headinguint8_tdeg/2Heading setpoint
target_distanceuint16_tdamDistance to target waypoint or position
throttleuint8_t%Throttle
airspeeduint8_tm/s*5Airspeed
airspeed_spuint8_tm/s*5Airspeed setpoint
groundspeeduint8_tm/s*5Groundspeed
windspeeduint8_tm/s*5Windspeed
wind_headinguint8_tdeg/2Wind heading
ephuint8_tdmMaximum error horizontal position since last message
epvuint8_tdmMaximum error vertical position since last message
temperature_airint8_tdegCAir temperature from airspeed sensor
climb_rateint8_tdm/sMaximum climb rate magnitude since last message
batteryint8_t%Battery (percentage, -1 for DNU)
wp_numuint16_tCurrent waypoint number
failure_flagsuint16_tHL_FAILURE_FLAGBitmap of failure flags.
custom0int8_tField for custom payload.
custom1int8_tField for custom payload.
custom2int8_tField for custom payload.

VIBRATION ( #241 )

Vibration levels and accelerometer clipping

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
vibration_xfloatVibration levels on X-axis
vibration_yfloatVibration levels on Y-axis
vibration_zfloatVibration levels on Z-axis
clipping_0uint32_tfirst accelerometer clipping count
clipping_1uint32_tsecond accelerometer clipping count
clipping_2uint32_tthird accelerometer clipping count

HOME_POSITION ( #242 )

This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. The position the system will return to and land on. 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.

Field NameTypeUnitsDescription
latitudeint32_tdegE7Latitude (WGS84)
longitudeint32_tdegE7Longitude (WGS84)
altitudeint32_tmmAltitude (MSL). Positive for up.
xfloatmLocal X position of this position in the local coordinate frame
yfloatmLocal Y position of this position in the local coordinate frame
zfloatmLocal Z position of this position in the local coordinate frame
qfloat[4]World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_xfloatmLocal X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_yfloatmLocal Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_zfloatmLocal Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
time_usec **uint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.

SET_HOME_POSITION ( #243 )

The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitly set by the operator before or after. 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.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID.
latitudeint32_tdegE7Latitude (WGS84)
longitudeint32_tdegE7Longitude (WGS84)
altitudeint32_tmmAltitude (MSL). Positive for up.
xfloatmLocal X position of this position in the local coordinate frame
yfloatmLocal Y position of this position in the local coordinate frame
zfloatmLocal Z position of this position in the local coordinate frame
qfloat[4]World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground
approach_xfloatmLocal X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_yfloatmLocal Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
approach_zfloatmLocal Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
time_usec **uint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.

MESSAGE_INTERVAL ( #244 )

The interval between messages for a particular MAVLink message ID. This interface replaces DATA_STREAM

Field NameTypeUnitsDescription
message_iduint16_tThe ID of the requested MAVLink message. v1.0 is limited to 254 messages.
interval_usint32_tusThe interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.

EXTENDED_SYS_STATE ( #245 )

Provides state for additional features

Field NameTypeValuesDescription
vtol_stateuint8_tMAV_VTOL_STATEThe VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration.
landed_stateuint8_tMAV_LANDED_STATEThe landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.

ADSB_VEHICLE ( #246 )

The location and information of an ADSB vehicle

Field NameTypeUnitsValuesDescription
ICAO_addressuint32_tICAO address
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
altitude_typeuint8_tADSB_ALTITUDE_TYPEADSB altitude type.
altitudeint32_tmmAltitude(ASL)
headinguint16_tcdegCourse over ground
hor_velocityuint16_tcm/sThe horizontal velocity
ver_velocityint16_tcm/sThe vertical velocity. Positive is up
callsignchar[9]The callsign, 8+null
emitter_typeuint8_tADSB_EMITTER_TYPEADSB emitter type.
tslcuint8_tsTime since last communication in seconds
flagsuint16_tADSB_FLAGSBitmap to indicate various statuses including valid data fields
squawkuint16_tSquawk code

COLLISION ( #247 )

Information about a potential collision

Field NameTypeUnitsValuesDescription
srcuint8_tMAV_COLLISION_SRCCollision data source
iduint32_tUnique identifier, domain based on src field
actionuint8_tMAV_COLLISION_ACTIONAction that is being taken to avoid this collision
threat_leveluint8_tMAV_COLLISION_THREAT_LEVELHow concerned the aircraft is about this collision
time_to_minimum_deltafloatsEstimated time until collision occurs
altitude_minimum_deltafloatmClosest vertical distance between vehicle and object
horizontal_minimum_deltafloatmClosest horizontal distance between vehicle and object

V2_EXTENSION ( #248 )

Message implementing parts of the V2 payload specs in V1 frames for transitional support.

Field NameTypeDescription
target_networkuint8_tNetwork ID (0 for broadcast)
target_systemuint8_tSystem ID (0 for broadcast)
target_componentuint8_tComponent ID (0 for broadcast)
message_typeuint16_tA code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
payloaduint8_t[249]Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.

MEMORY_VECT ( #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.

Field NameTypeDescription
addressuint16_tStarting address of the debug variables
veruint8_tVersion code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
typeuint8_tType code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
valueint8_t[32]Memory contents at specified address

DEBUG_VECT ( #250 )

To debug something using a named 3D vector.

Field NameTypeUnitsDescription
namechar[10]Name
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
xfloatx
yfloaty
zfloatz

NAMED_VALUE_FLOAT ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
namechar[10]Name of the debug variable
valuefloatFloating point value

NAMED_VALUE_INT ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
namechar[10]Name of the debug variable
valueint32_tSigned integer value

STATUSTEXT ( #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).

Field NameTypeValuesDescription
severityuint8_tMAV_SEVERITYSeverity of status. Relies on the definitions within RFC-5424.
textchar[50]Status text message, without null termination character

DEBUG ( #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.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
induint8_tindex of debug variable
valuefloatDEBUG value

SETUP_SIGNING ( #256 )

(MAVLink 2) Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing

Field NameTypeDescription
target_systemuint8_tsystem id of the target
target_componentuint8_tcomponent ID of the target
secret_keyuint8_t[32]signing key
initial_timestampuint64_tinitial timestamp

BUTTON_CHANGE ( #257 )

(MAVLink 2) Report button state change.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
last_change_msuint32_tmsTime of last change of button state.
stateuint8_tBitmap for state of buttons.

PLAY_TUNE ( #258 )

(MAVLink 2) Control vehicle tone generation (buzzer)

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
tunechar[30]tune in board specific format
tune2 **char[200]tune extension (appended to tune)

CAMERA_INFORMATION ( #259 )

(MAVLink 2) Information about a camera

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
vendor_nameuint8_t[32]Name of the camera vendor
model_nameuint8_t[32]Name of the camera model
firmware_versionuint32_tVersion of the camera firmware (v << 24 & 0xff = Dev, v << 16 & 0xff = Patch, v << 8 & 0xff = Minor, v & 0xff = Major)
focal_lengthfloatmmFocal length
sensor_size_hfloatmmImage sensor size horizontal
sensor_size_vfloatmmImage sensor size vertical
resolution_huint16_tpixHorizontal image resolution
resolution_vuint16_tpixVertical image resolution
lens_iduint8_tReserved for a lens ID
flagsuint32_tCAMERA_CAP_FLAGSBitmap of camera capability flags.
cam_definition_versionuint16_tCamera definition version (iteration)
cam_definition_urichar[140]Camera definition URI (if any, otherwise only basic functions will be available).

CAMERA_SETTINGS ( #260 )

(MAVLink 2) Settings of a camera, can be requested using MAV_CMD_REQUEST_CAMERA_SETTINGS.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
mode_iduint8_tCAMERA_MODECamera mode
zoomLevel **floatCurrent zoom level (0.0 to 100.0, NaN if not known)
focusLevel **floatCurrent focus level (0.0 to 100.0, NaN if not known)

STORAGE_INFORMATION ( #261 )

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

(MAVLink 2) Information about a storage medium.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
storage_iduint8_tStorage ID (1 for first, 2 for second, etc.)
storage_countuint8_tNumber of storage devices
statusuint8_tStatus of storage (0 not available, 1 unformatted, 2 formatted)
total_capacityfloatMiBTotal capacity.
used_capacityfloatMiBUsed capacity.
available_capacityfloatMiBAvailable storage capacity.
read_speedfloatMiB/sRead speed.
write_speedfloatMiB/sWrite speed.

CAMERA_CAPTURE_STATUS ( #262 )

(MAVLink 2) Information about the status of a capture.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
image_statusuint8_tCurrent status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
video_statusuint8_tCurrent status of video capturing (0: idle, 1: capture in progress)
image_intervalfloatsImage capture interval
recording_time_msuint32_tmsTime since recording started
available_capacityfloatMiBAvailable storage capacity.

CAMERA_IMAGE_CAPTURED ( #263 )

(MAVLink 2) Information about a captured image

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
time_utcuint64_tusTimestamp (time since UNIX epoch) in UTC. 0 for unknown.
camera_iduint8_tCamera ID (1 for first, 2 for second, etc.)
latint32_tdegE7Latitude where image was taken
lonint32_tdegE7Longitude where capture was taken
altint32_tmmAltitude (MSL) where image was taken
relative_altint32_tmmAltitude above ground
qfloat[4]Quaternion of camera orientation (w, x, y, z order, zero-rotation is 0, 0, 0, 0)
image_indexint32_tZero based index of this image (image count since armed -1)
capture_resultint8_tBoolean indicating success (1) or failure (0) while capturing this image.
file_urlchar[205]URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.

FLIGHT_INFORMATION ( #264 )

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

(MAVLink 2) Information about flight since last arming.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
arming_time_utcuint64_tusTimestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
takeoff_time_utcuint64_tusTimestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
flight_uuiduint64_tUniversally unique identifier (UUID) of flight, should correspond to name of log files

MOUNT_ORIENTATION ( #265 )

(MAVLink 2) Orientation of a mount

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
rollfloatdegRoll in global frame (set to NaN for invalid).
pitchfloatdegPitch in global frame (set to NaN for invalid).
yawfloatdegYaw relative to vehicle(set to NaN for invalid).
yaw_absolute **floatdegYaw in absolute frame, North is 0 (set to NaN for invalid).

LOGGING_DATA ( #266 )

(MAVLink 2) A message containing logged data (see also MAV_CMD_LOGGING_START)

Field NameTypeUnitsDescription
target_systemuint8_tsystem ID of the target
target_componentuint8_tcomponent ID of the target
sequenceuint16_tsequence number (can wrap)
lengthuint8_tbytesdata length
first_message_offsetuint8_tbytesoffset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
datauint8_t[249]logged data

LOGGING_DATA_ACKED ( #267 )

(MAVLink 2) A message containing logged data which requires a LOGGING_ACK to be sent back

Field NameTypeUnitsDescription
target_systemuint8_tsystem ID of the target
target_componentuint8_tcomponent ID of the target
sequenceuint16_tsequence number (can wrap)
lengthuint8_tbytesdata length
first_message_offsetuint8_tbytesoffset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
datauint8_t[249]logged data

LOGGING_ACK ( #268 )

(MAVLink 2) An ack for a LOGGING_DATA_ACKED message

Field NameTypeDescription
target_systemuint8_tsystem ID of the target
target_componentuint8_tcomponent ID of the target
sequenceuint16_tsequence number (must match the one in LOGGING_DATA_ACKED)

VIDEO_STREAM_INFORMATION ( #269 )

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

(MAVLink 2) Information about video stream

Field NameTypeUnitsValuesDescription
stream_iduint8_tStream ID (1 for first, 2 for second, etc.)
countuint8_tNumber of streams available
flagsuint16_tVIDEO_STREAM_STATUS_FLAGSBitmap of stream status flags
frameratefloatHzFrame rate
resolution_huint16_tpixHorizontal resolution
resolution_vuint16_tpixVertical resolution
bitrateuint32_tbits/sBit rate in bits per second
rotationuint16_tdegVideo image rotation clockwise
hfovuint16_tdegHorizontal Field of view
urichar[160]Video stream URI

SET_VIDEO_STREAM_SETTINGS ( #270 )

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

(MAVLink 2) Message that sets video stream settings

Field NameTypeUnitsDescription
target_systemuint8_tsystem ID of the target
target_componentuint8_tcomponent ID of the target
camera_iduint8_tStream ID (1 for first, 2 for second, etc.)
frameratefloatHzFrame rate (set to -1 for highest framerate possible)
resolution_huint16_tpixHorizontal resolution (set to -1 for highest resolution possible)
resolution_vuint16_tpixVertical resolution (set to -1 for highest resolution possible)
bitrateuint32_tbits/sBit rate (set to -1 for auto)
rotationuint16_tdegVideo image rotation clockwise (0-359 degrees)
urichar[160]Video stream URI (mostly for UDP/RTP)

WIFI_CONFIG_AP ( #299 )

(MAVLink 2) Configure AP SSID and Password.

Field NameTypeDescription
ssidchar[32]Name of Wi-Fi network (SSID). Leave it blank to leave it unchanged.
passwordchar[64]Password. Leave it blank for an open AP.

PROTOCOL_VERSION ( #300 )

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

(MAVLink 2) Version and capability of protocol version. This message is the response to REQUEST_PROTOCOL_VERSION and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to REQUEST_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.

Field NameTypeDescription
versionuint16_tCurrently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
min_versionuint16_tMinimum MAVLink version supported
max_versionuint16_tMaximum MAVLink version supported (set to the same value as version by default)
spec_version_hashuint8_t[8]The first 8 bytes (not characters printed in hex!) of the git hash.
library_version_hashuint8_t[8]The first 8 bytes (not characters printed in hex!) of the git hash.

UAVCAN_NODE_STATUS ( #310 )

(MAVLink 2) 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.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
uptime_secuint32_tsTime since the start-up of the node.
healthuint8_tUAVCAN_NODE_HEALTHGeneralized node health status.
modeuint8_tUAVCAN_NODE_MODEGeneralized operating mode.
sub_modeuint8_tNot used currently.
vendor_specific_status_codeuint16_tVendor-specific status information.

UAVCAN_NODE_INFO ( #311 )

(MAVLink 2) 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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
uptime_secuint32_tsTime since the start-up of the node.
namechar[80]Node name string. For example, "sapog.px4.io".
hw_version_majoruint8_tHardware major version number.
hw_version_minoruint8_tHardware minor version number.
hw_unique_iduint8_t[16]Hardware unique 128-bit ID.
sw_version_majoruint8_tSoftware major version number.
sw_version_minoruint8_tSoftware minor version number.
sw_vcs_commituint32_tVersion control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown.

PARAM_EXT_REQUEST_READ ( #320 )

(MAVLink 2) Request to read the value of a parameter with the either the param_id string id or param_index.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
param_idchar[16]Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_indexint16_tParameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)

PARAM_EXT_REQUEST_LIST ( #321 )

(MAVLink 2) Request all parameters of this component. After this request, all parameters are emitted.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

PARAM_EXT_VALUE ( #322 )

(MAVLink 2) 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.

Field NameTypeValuesDescription
param_idchar[16]Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_valuechar[128]Parameter value
param_typeuint8_tMAV_PARAM_EXT_TYPEParameter type.
param_countuint16_tTotal number of parameters
param_indexuint16_tIndex of this parameter

PARAM_EXT_SET ( #323 )

(MAVLink 2) 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.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
param_idchar[16]Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_valuechar[128]Parameter value
param_typeuint8_tMAV_PARAM_EXT_TYPEParameter type.

PARAM_EXT_ACK ( #324 )

(MAVLink 2) Response from a PARAM_EXT_SET message.

Field NameTypeValuesDescription
param_idchar[16]Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_valuechar[128]Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)
param_typeuint8_tMAV_PARAM_EXT_TYPEParameter type.
param_resultuint8_tPARAM_ACKResult code.

OBSTACLE_DISTANCE ( #330 )

(MAVLink 2) Obstacle distances in front of the sensor, starting from the left in increment degrees to the right

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
sensor_typeuint8_tMAV_DISTANCE_SENSORClass id of the distance sensor type.
distancesuint16_t[72]cmDistance of obstacles around the UAV with index 0 corresponding to local North. A value of 0 means that the obstacle is right in front of the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
incrementuint8_tdegAngular width in degrees of each array element.
min_distanceuint16_tcmMinimum distance the sensor can measure.
max_distanceuint16_tcmMaximum distance the sensor can measure.

ODOMETRY ( #331 )

(MAVLink 2) 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).

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
frame_iduint8_tMAV_FRAMECoordinate frame of reference for the pose data.
child_frame_iduint8_tMAV_FRAMECoordinate frame of reference for the velocity in free space (twist) data.
xfloatmX Position
yfloatmY Position
zfloatmZ Position
qfloat[4]Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
vxfloatm/sX linear speed
vyfloatm/sY linear speed
vzfloatm/sZ linear speed
rollspeedfloatrad/sRoll angular speed
pitchspeedfloatrad/sPitch angular speed
yawspeedfloatrad/sYaw angular speed
pose_covariancefloat[21]Pose (states: x, y, z, roll, pitch, yaw) covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.)
twist_covariancefloat[21]Twist (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed) covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.)

TRAJECTORY_REPRESENTATION_WAYPOINTS ( #332 )

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

(MAVLink 2) Describe a trajectory using an array of up-to 5 waypoints in the local frame.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
valid_pointsuint8_tNumber of valid points (up-to 5 waypoints are possible)
pos_xfloat[5]mX-coordinate of waypoint, set to NaN if not being used
pos_yfloat[5]mY-coordinate of waypoint, set to NaN if not being used
pos_zfloat[5]mZ-coordinate of waypoint, set to NaN if not being used
vel_xfloat[5]m/sX-velocity of waypoint, set to NaN if not being used
vel_yfloat[5]m/sY-velocity of waypoint, set to NaN if not being used
vel_zfloat[5]m/sZ-velocity of waypoint, set to NaN if not being used
acc_xfloat[5]m/s/sX-acceleration of waypoint, set to NaN if not being used
acc_yfloat[5]m/s/sY-acceleration of waypoint, set to NaN if not being used
acc_zfloat[5]m/s/sZ-acceleration of waypoint, set to NaN if not being used
pos_yawfloat[5]radYaw angle, set to NaN if not being used
vel_yawfloat[5]rad/sYaw rate, set to NaN if not being used

TRAJECTORY_REPRESENTATION_BEZIER ( #333 )

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

(MAVLink 2) Describe a trajectory using an array of up-to 5 bezier points in the local frame.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
valid_pointsuint8_tNumber of valid points (up-to 5 waypoints are possible)
pos_xfloat[5]mX-coordinate of starting bezier point, set to NaN if not being used
pos_yfloat[5]mY-coordinate of starting bezier point, set to NaN if not being used
pos_zfloat[5]mZ-coordinate of starting bezier point, set to NaN if not being used
deltafloat[5]sBezier time horizon, set to NaN if velocity/acceleration should not be incorporated
pos_yawfloat[5]radYaw, set to NaN for unchanged

UTM_GLOBAL_POSITION ( #340 )

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

(MAVLink 2) The global position resulting from GPS and sensor fusion.

Field NameTypeUnitsValuesDescription
timeuint64_tusTime of applicability of position (microseconds since UNIX epoch).
uas_iduint8_t[18]Unique UAS ID.
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altint32_tmmAltitude (WGS84)
relative_altint32_tmmAltitude above ground
vxint16_tcm/sGround X speed (latitude, positive north)
vyint16_tcm/sGround Y speed (longitude, positive east)
vzint16_tcm/sGround Z speed (altitude, positive down)
h_accuint16_tmmHorizontal position uncertainty (standard deviation)
v_accuint16_tmmAltitude uncertainty (standard deviation)
vel_accuint16_tcm/sSpeed uncertainty (standard deviation)
next_latint32_tdegE7Next waypoint, latitude (WGS84)
next_lonint32_tdegE7Next waypoint, longitude (WGS84)
next_altint32_tmmNext waypoint, altitude (WGS84)
update_rateuint16_tSeconds * 1E2 until next update. Set to 0 if unknown or in data driven mode.
flight_stateuint8_tUTM_FLIGHT_STATEFlight state
flagsuint8_tUTM_DATA_AVAIL_FLAGSBitwise OR combination of the data available flags.

DEBUG_FLOAT_ARRAY ( #350 )

(MAVLink 2) 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.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
namechar[10]Name, for human-friendly display in a Ground Control Station
array_iduint16_tUnique ID used to discriminate between arrays
data **float[58]data

ORBIT_EXECUTION_STATUS ( #360 )

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

(MAVLink 2) Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT).

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
radiusfloatmRadius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
frameuint8_tMAV_FRAMEThe coordinate system of the fields: x, y, z.
xint32_tX coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
yint32_tY coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
zfloatmAltitude of center point. Coordinate system depends on frame field.

results matching ""

    No results matching ""