MAVLINK Common Message Set

The MAVLink common message set contains standard definitions that are managed by the MAVLink project. The definitions cover functionality that is considered useful to most ground control stations and autopilots. MAVLink-compatible systems are expected to use these definitions where possible (if an appropriate message exists) rather than rolling out variants in their own dialects.

The original definitions are defined in common.xml.

The common set includes minimal.xml, which contains the minimal set of definitions for any MAVLink system. These definitions are reproduced at the end of this topic.

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.

MAVLink Include Files: standard.xml

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

This file has protocol dialect: 0.

MAVLink Type Enumerations

FIRMWARE_VERSION_TYPE

[Enum] 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

[Enum] Flags to report failure cases over the high latency telemetry.

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_GOTO

[Enum] Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.

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

[Enum] 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_SYS_STATUS_SENSOR

[Enum] 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
268435456MAV_SYS_STATUS_PREARM_CHECK0x10000000 pre-arm check status. Always healthy when armed
536870912MAV_SYS_STATUS_OBSTACLE_AVOIDANCE0x20000000 Avoidance/collision prevention
1073741824MAV_SYS_STATUS_SENSOR_PROPULSION0x40000000 propulsion (actuator, esc, motor or propellor)
2147483648MAV_SYS_STATUS_EXTENSION_USED0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)

MAV_SYS_STATUS_SENSOR_EXTENDED

[Enum] These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields.

ValueField NameDescription
1MAV_SYS_STATUS_RECOVERY_SYSTEM0x01 Recovery system (parachute, balloon, retracts etc)

MAV_FRAME

[Enum] Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - "GLOBAL": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with "GLOBAL": - "RELATIVE_ALT": Altitude is relative to the vehicle home position rather than MSL. - "TERRAIN_ALT": Altitude is relative to ground level rather than MSL. - "INT": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - "LOCAL": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator ("EKF"). - "BODY": Origin of local frame travels with the vehicle. NOTE, "BODY" does NOT indicate alignment of frame axis with vehicle attitude. - "OFFSET": Deprecated synonym for "BODY" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).

ValueField NameDescription
0MAV_FRAME_GLOBALGlobal (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
1MAV_FRAME_LOCAL_NEDNED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
2MAV_FRAME_MISSIONNOT a coordinate frame, indicates a mission command.
3MAV_FRAME_GLOBAL_RELATIVE_ALTGlobal (WGS84) coordinate frame + altitude relative 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 position.
4MAV_FRAME_LOCAL_ENUENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.
5MAV_FRAME_GLOBAL_INTGlobal (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude over mean sea level (MSL).
6MAV_FRAME_GLOBAL_RELATIVE_ALT_INTGlobal (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude with 0 being at the altitude of the home position.
7MAV_FRAME_LOCAL_OFFSET_NEDNED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.
8MAV_FRAME_BODY_NED

DEPRECATED: Replaced by MAV_FRAME_BODY_FRD (2019-08).

Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.
9MAV_FRAME_BODY_OFFSET_NED

DEPRECATED: Replaced by MAV_FRAME_BODY_FRD (2019-08).

This is the same as MAV_FRAME_BODY_FRD.
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 (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees*1E7, second value / y: longitude in degrees*1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
12MAV_FRAME_BODY_FRDFRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
13MAV_FRAME_RESERVED_13

DEPRECATED: Replaced by (2019-04).

MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
14MAV_FRAME_RESERVED_14

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FRD (2019-04).

MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).
15MAV_FRAME_RESERVED_15

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FLU (2019-04).

MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).
16MAV_FRAME_RESERVED_16

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FRD (2019-04).

MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).
17MAV_FRAME_RESERVED_17

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FLU (2019-04).

MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up).
18MAV_FRAME_RESERVED_18

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FRD (2019-04).

MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down).
19MAV_FRAME_RESERVED_19

DEPRECATED: Replaced by MAV_FRAME_LOCAL_FLU (2019-04).

MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up).
20MAV_FRAME_LOCAL_FRDFRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
21MAV_FRAME_LOCAL_FLUFLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.

[Enum]

ValueField NameDescription

FENCE_ACTION

[Enum] Actions following geofence breach.

ValueField NameDescription
0FENCE_ACTION_NONEDisable fenced mode. If used in a plan this would mean the next fence is disabled.
1FENCE_ACTION_GUIDEDFly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.
2FENCE_ACTION_REPORTReport fence breach, but don't take action
3FENCE_ACTION_GUIDED_THR_PASSFly to geofence MAV_CMD_NAV_FENCE_RETURN_POINT with manual throttle control in GUIDED mode. Note: This action is only supported by ArduPlane, and may not be supported in all versions.
4FENCE_ACTION_RTLReturn/RTL mode.
5FENCE_ACTION_HOLDHold at current location.
6FENCE_ACTION_TERMINATETermination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions).
7FENCE_ACTION_LANDLand at current location.

FENCE_BREACH

[Enum]

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

FENCE_MITIGATE

[Enum] Actions being taken to mitigate/prevent fence breach

ValueField NameDescription
0FENCE_MITIGATE_UNKNOWNUnknown
1FENCE_MITIGATE_NONENo actions being taken
2FENCE_MITIGATE_VEL_LIMITVelocity limiting active to prevent breach

FENCE_TYPE

[Enum]

ValueField NameDescription
0FENCE_TYPE_ALLAll fence types
1FENCE_TYPE_ALT_MAXMaximum altitude fence
2FENCE_TYPE_CIRCLECircle fence
4FENCE_TYPE_POLYGONPolygon fence
8FENCE_TYPE_ALT_MINMinimum altitude fence

MAV_MOUNT_MODE

DEPRECATED: Replaced by GIMBAL_MANAGER_FLAGS (2020-01).

[Enum] Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.

ValueField NameDescription
0MAV_MOUNT_MODE_RETRACTLoad and keep safe position (Roll,Pitch,Yaw) from permanent 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
5MAV_MOUNT_MODE_SYSID_TARGETGimbal tracks system with specified system ID
6MAV_MOUNT_MODE_HOME_LOCATIONGimbal tracks home position

GIMBAL_DEVICE_CAP_FLAGS

[Enum] Gimbal device (low level) capability flags (bitmap).

ValueField NameDescription
1GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACTGimbal device supports a retracted position.
2GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRALGimbal device supports a horizontal, forward looking position, stabilized.
4GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXISGimbal device supports rotating around roll axis.
8GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOWGimbal device supports to follow a roll angle relative to the vehicle.
16GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCKGimbal device supports locking to a roll angle (generally that's the default with roll stabilized).
32GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXISGimbal device supports rotating around pitch axis.
64GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOWGimbal device supports to follow a pitch angle relative to the vehicle.
128GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCKGimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized).
256GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXISGimbal device supports rotating around yaw axis.
512GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOWGimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).
1024GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCKGimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).
2048GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAWGimbal device supports yawing/panning infinitely (e.g. using slip disk).
4096GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAMEGimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME.
8192GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTSGimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation.

GIMBAL_MANAGER_CAP_FLAGS

[Enum] Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags.

ValueField NameDescription
1GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACTBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT.
2GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRALBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL.
4GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXISBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS.
8GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOWBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW.
16GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCKBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK.
32GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXISBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS.
64GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOWBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW.
128GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCKBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK.
256GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXISBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS.
512GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOWBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW.
1024GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCKBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK.
2048GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAWBased on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW.
4096GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAMEBased on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME.
8192GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTSBased on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS.
65536GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCALGimbal manager supports to point to a local position.
131072GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBALGimbal manager supports to point to a global latitude, longitude, altitude position.

GIMBAL_DEVICE_FLAGS

[Enum] Flags for gimbal device (lower level) operation.

ValueField NameDescription
1GIMBAL_DEVICE_FLAGS_RETRACTSet to retracted safe position (no stabilization), takes precedence over all other flags.
2GIMBAL_DEVICE_FLAGS_NEUTRALSet to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation.
4GIMBAL_DEVICE_FLAGS_ROLL_LOCKLock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.
8GIMBAL_DEVICE_FLAGS_PITCH_LOCKLock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.
16GIMBAL_DEVICE_FLAGS_YAW_LOCKLock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward).
32GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAMEYaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward).
64GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAMEYaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).
128GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAMEGimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored).
256GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVEThe gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored.
512GIMBAL_DEVICE_FLAGS_RC_MIXEDThe gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation.

GIMBAL_MANAGER_FLAGS

[Enum] Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.

ValueField NameDescription
1GIMBAL_MANAGER_FLAGS_RETRACTBased on GIMBAL_DEVICE_FLAGS_RETRACT.
2GIMBAL_MANAGER_FLAGS_NEUTRALBased on GIMBAL_DEVICE_FLAGS_NEUTRAL.
4GIMBAL_MANAGER_FLAGS_ROLL_LOCKBased on GIMBAL_DEVICE_FLAGS_ROLL_LOCK.
8GIMBAL_MANAGER_FLAGS_PITCH_LOCKBased on GIMBAL_DEVICE_FLAGS_PITCH_LOCK.
16GIMBAL_MANAGER_FLAGS_YAW_LOCKBased on GIMBAL_DEVICE_FLAGS_YAW_LOCK.
32GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAMEBased on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME.
64GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAMEBased on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.
128GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAMEBased on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME.
256GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVEBased on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE.
512GIMBAL_MANAGER_FLAGS_RC_MIXEDBased on GIMBAL_DEVICE_FLAGS_RC_MIXED.

GIMBAL_DEVICE_ERROR_FLAGS

[Enum] Gimbal device (low level) error flags (bitmap, 0 means no error)

ValueField NameDescription
1GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMITGimbal device is limited by hardware roll limit.
2GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMITGimbal device is limited by hardware pitch limit.
4GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMITGimbal device is limited by hardware yaw limit.
8GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERRORThere is an error with the gimbal encoders.
16GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERRORThere is an error with the gimbal power source.
32GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERRORThere is an error with the gimbal motors.
64GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERRORThere is an error with the gimbal's software.
128GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERRORThere is an error with the gimbal's communication.
256GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNINGGimbal device is currently calibrating.
512GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGERGimbal device is not assigned to a gimbal manager.

GRIPPER_ACTIONS

[Enum] Gripper actions.

ValueField NameDescription
0GRIPPER_ACTION_RELEASEGripper release cargo.
1GRIPPER_ACTION_GRABGripper grab onto cargo.

WINCH_ACTIONS

[Enum] Winch actions.

ValueField NameDescription
0WINCH_RELAXEDAllow motor to freewheel.
1WINCH_RELATIVE_LENGTH_CONTROLWind or unwind specified length of line, optionally using specified rate.
2WINCH_RATE_CONTROLWind or unwind line at specified rate.
3WINCH_LOCKPerform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored.
4WINCH_DELIVERSequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored.
5WINCH_HOLDEngage motor and hold current position. Only action and instance command parameters are used, others are ignored.
6WINCH_RETRACTReturn the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored.
7WINCH_LOAD_LINELoad the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored.
8WINCH_ABANDON_LINESpool out the entire length of the line. Only action and instance command parameters are used, others are ignored.
9WINCH_LOAD_PAYLOADSpools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored

UAVCAN_NODE_HEALTH

[Enum] 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

[Enum] 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.

ESC_CONNECTION_TYPE

[Enum] Indicates the ESC connection type.

ValueField NameDescription
0ESC_CONNECTION_TYPE_PPMTraditional PPM ESC.
1ESC_CONNECTION_TYPE_SERIALSerial Bus connected ESC.
2ESC_CONNECTION_TYPE_ONESHOTOne Shot PPM ESC.
3ESC_CONNECTION_TYPE_I2CI2C ESC.
4ESC_CONNECTION_TYPE_CANCAN-Bus ESC.
5ESC_CONNECTION_TYPE_DSHOTDShot ESC.

ESC_FAILURE_FLAGS

[Enum] Flags to report ESC failures.

ValueField NameDescription
0ESC_FAILURE_NONENo ESC failure.
1ESC_FAILURE_OVER_CURRENTOver current failure.
2ESC_FAILURE_OVER_VOLTAGEOver voltage failure.
4ESC_FAILURE_OVER_TEMPERATUREOver temperature failure.
8ESC_FAILURE_OVER_RPMOver RPM failure.
16ESC_FAILURE_INCONSISTENT_CMDInconsistent command failure i.e. out of bounds.
32ESC_FAILURE_MOTOR_STUCKMotor stuck failure.
64ESC_FAILURE_GENERICGeneric ESC failure.

STORAGE_STATUS

[Enum] Flags to indicate the status of camera storage.

ValueField NameDescription
0STORAGE_STATUS_EMPTYStorage is missing (no microSD card loaded for example.)
1STORAGE_STATUS_UNFORMATTEDStorage present but unformatted.
2STORAGE_STATUS_READYStorage present and ready.
3STORAGE_STATUS_NOT_SUPPORTEDCamera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored.

STORAGE_TYPE

[Enum] Flags to indicate the type of storage.

ValueField NameDescription
0STORAGE_TYPE_UNKNOWNStorage type is not known.
1STORAGE_TYPE_USB_STICKStorage type is USB device.
2STORAGE_TYPE_SDStorage type is SD card.
3STORAGE_TYPE_MICROSDStorage type is microSD card.
4STORAGE_TYPE_CFStorage type is CFast.
5STORAGE_TYPE_CFEStorage type is CFexpress.
6STORAGE_TYPE_XQDStorage type is XQD.
7STORAGE_TYPE_HDStorage type is HD mass storage type.
254STORAGE_TYPE_OTHERStorage type is other, not listed type.

STORAGE_USAGE_FLAG

[Enum] Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).

ValueField NameDescription
1STORAGE_USAGE_FLAG_SETAlways set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported).
2STORAGE_USAGE_FLAG_PHOTOStorage for saving photos.
4STORAGE_USAGE_FLAG_VIDEOStorage for saving videos.
8STORAGE_USAGE_FLAG_LOGSStorage for saving logs.

ORBIT_YAW_BEHAVIOUR

[Enum] Yaw behaviour during orbit flight.

ValueField NameDescription
0ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTERVehicle front points to the center (default).
1ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADINGVehicle front holds heading when message received.
2ORBIT_YAW_BEHAVIOUR_UNCONTROLLEDYaw uncontrolled.
3ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLEVehicle front follows flight path (tangential to circle).
4ORBIT_YAW_BEHAVIOUR_RC_CONTROLLEDYaw controlled by RC input.

WIFI_CONFIG_AP_RESPONSE

[Enum] Possible responses from a WIFI_CONFIG_AP message.

ValueField NameDescription
0WIFI_CONFIG_AP_RESPONSE_UNDEFINEDUndefined response. Likely an indicative of a system that doesn't support this request.
1WIFI_CONFIG_AP_RESPONSE_ACCEPTEDChanges accepted.
2WIFI_CONFIG_AP_RESPONSE_REJECTEDChanges rejected.
3WIFI_CONFIG_AP_RESPONSE_MODE_ERRORInvalid Mode.
4WIFI_CONFIG_AP_RESPONSE_SSID_ERRORInvalid SSID.
5WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERRORInvalid Password.

CELLULAR_CONFIG_RESPONSE

[Enum] Possible responses from a CELLULAR_CONFIG message.

ValueField NameDescription
0CELLULAR_CONFIG_RESPONSE_ACCEPTEDChanges accepted.
1CELLULAR_CONFIG_RESPONSE_APN_ERRORInvalid APN.
2CELLULAR_CONFIG_RESPONSE_PIN_ERRORInvalid PIN.
3CELLULAR_CONFIG_RESPONSE_REJECTEDChanges rejected.
4CELLULAR_CONFIG_BLOCKED_PUK_REQUIREDPUK is required to unblock SIM card.

WIFI_CONFIG_AP_MODE

[Enum] WiFi Mode.

ValueField NameDescription
0WIFI_CONFIG_AP_MODE_UNDEFINEDWiFi mode is undefined.
1WIFI_CONFIG_AP_MODE_APWiFi configured as an access point.
2WIFI_CONFIG_AP_MODE_STATIONWiFi configured as a station connected to an existing local WiFi network.
3WIFI_CONFIG_AP_MODE_DISABLEDWiFi disabled.

COMP_METADATA_TYPE

[Enum] Supported component metadata types. These are used in the "general" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages.

ValueField NameDescription
0COMP_METADATA_TYPE_GENERALGeneral information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI.
1COMP_METADATA_TYPE_PARAMETERParameter meta data.
2COMP_METADATA_TYPE_COMMANDSMeta data that specifies which commands and command parameters the vehicle supports. (WIP)
3COMP_METADATA_TYPE_PERIPHERALSMeta data that specifies external non-MAVLink peripherals.
4COMP_METADATA_TYPE_EVENTSMeta data for the events interface.
5COMP_METADATA_TYPE_ACTUATORSMeta data for actuator configuration (motors, servos and vehicle geometry) and testing.

ACTUATOR_CONFIGURATION

[Enum] Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.

ValueField NameDescription
0ACTUATOR_CONFIGURATION_NONEDo nothing.
1ACTUATOR_CONFIGURATION_BEEPCommand the actuator to beep now.
2ACTUATOR_CONFIGURATION_3D_MODE_ONPermanently set the actuator (ESC) to 3D mode (reversible thrust).
3ACTUATOR_CONFIGURATION_3D_MODE_OFFPermanently set the actuator (ESC) to non 3D mode (non-reversible thrust).
4ACTUATOR_CONFIGURATION_SPIN_DIRECTION1Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise).
5ACTUATOR_CONFIGURATION_SPIN_DIRECTION2Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1).

ACTUATOR_OUTPUT_FUNCTION

[Enum] Actuator output function. Values greater or equal to 1000 are autopilot-specific.

ValueField NameDescription
0ACTUATOR_OUTPUT_FUNCTION_NONENo function (disabled).
1ACTUATOR_OUTPUT_FUNCTION_MOTOR1Motor 1
2ACTUATOR_OUTPUT_FUNCTION_MOTOR2Motor 2
3ACTUATOR_OUTPUT_FUNCTION_MOTOR3Motor 3
4ACTUATOR_OUTPUT_FUNCTION_MOTOR4Motor 4
5ACTUATOR_OUTPUT_FUNCTION_MOTOR5Motor 5
6ACTUATOR_OUTPUT_FUNCTION_MOTOR6Motor 6
7ACTUATOR_OUTPUT_FUNCTION_MOTOR7Motor 7
8ACTUATOR_OUTPUT_FUNCTION_MOTOR8Motor 8
9ACTUATOR_OUTPUT_FUNCTION_MOTOR9Motor 9
10ACTUATOR_OUTPUT_FUNCTION_MOTOR10Motor 10
11ACTUATOR_OUTPUT_FUNCTION_MOTOR11Motor 11
12ACTUATOR_OUTPUT_FUNCTION_MOTOR12Motor 12
13ACTUATOR_OUTPUT_FUNCTION_MOTOR13Motor 13
14ACTUATOR_OUTPUT_FUNCTION_MOTOR14Motor 14
15ACTUATOR_OUTPUT_FUNCTION_MOTOR15Motor 15
16ACTUATOR_OUTPUT_FUNCTION_MOTOR16Motor 16
33ACTUATOR_OUTPUT_FUNCTION_SERVO1Servo 1
34ACTUATOR_OUTPUT_FUNCTION_SERVO2Servo 2
35ACTUATOR_OUTPUT_FUNCTION_SERVO3Servo 3
36ACTUATOR_OUTPUT_FUNCTION_SERVO4Servo 4
37ACTUATOR_OUTPUT_FUNCTION_SERVO5Servo 5
38ACTUATOR_OUTPUT_FUNCTION_SERVO6Servo 6
39ACTUATOR_OUTPUT_FUNCTION_SERVO7Servo 7
40ACTUATOR_OUTPUT_FUNCTION_SERVO8Servo 8
41ACTUATOR_OUTPUT_FUNCTION_SERVO9Servo 9
42ACTUATOR_OUTPUT_FUNCTION_SERVO10Servo 10
43ACTUATOR_OUTPUT_FUNCTION_SERVO11Servo 11
44ACTUATOR_OUTPUT_FUNCTION_SERVO12Servo 12
45ACTUATOR_OUTPUT_FUNCTION_SERVO13Servo 13
46ACTUATOR_OUTPUT_FUNCTION_SERVO14Servo 14
47ACTUATOR_OUTPUT_FUNCTION_SERVO15Servo 15
48ACTUATOR_OUTPUT_FUNCTION_SERVO16Servo 16

AUTOTUNE_AXIS

[Enum] Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.

ValueField NameDescription
0AUTOTUNE_AXIS_DEFAULTFlight stack tunes axis according to its default settings.
1AUTOTUNE_AXIS_ROLLAutotune roll axis.
2AUTOTUNE_AXIS_PITCHAutotune pitch axis.
4AUTOTUNE_AXIS_YAWAutotune yaw axis.

PREFLIGHT_STORAGE_PARAMETER_ACTION

[Enum] Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

ValueField NameDescription
0PARAM_READ_PERSISTENTRead all parameters from persistent storage. Replaces values in volatile storage.
1PARAM_WRITE_PERSISTENTWrite all parameter values to persistent storage (flash/EEPROM)
2PARAM_RESET_CONFIG_DEFAULTReset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics.
3PARAM_RESET_SENSOR_DEFAULTReset only sensor calibration parameters to factory defaults (or firmware default if not available)
4PARAM_RESET_ALL_DEFAULTReset all parameters, including operation counters, to default values

PREFLIGHT_STORAGE_MISSION_ACTION

[Enum] Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)

ValueField NameDescription
0MISSION_READ_PERSISTENTRead current mission data from persistent storage
1MISSION_WRITE_PERSISTENTWrite current mission data to persistent storage
2MISSION_RESET_DEFAULTErase all mission data stored on the vehicle (both persistent and volatile storage)

MAV_DATA_STREAM

DEPRECATED: Replaced by MESSAGE_INTERVAL (2015-06).

[Enum] 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_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).

[Enum] 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_PARAM_TYPE

[Enum] 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

[Enum] 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

[Enum] Result from a MAVLink command (MAV_CMD)

ValueField NameDescription
0MAV_RESULT_ACCEPTEDCommand is valid (is supported and has valid parameters), and was executed.
1MAV_RESULT_TEMPORARILY_REJECTEDCommand is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work.
2MAV_RESULT_DENIEDCommand is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work.
3MAV_RESULT_UNSUPPORTEDCommand is not supported (unknown).
4MAV_RESULT_FAILEDCommand is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc.
5MAV_RESULT_IN_PROGRESSCommand is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation.
6MAV_RESULT_CANCELLEDCommand has been cancelled (as a result of receiving a COMMAND_CANCEL message).
7MAV_RESULT_COMMAND_LONG_ONLYCommand is only accepted when sent as a COMMAND_LONG.
8MAV_RESULT_COMMAND_INT_ONLYCommand is only accepted when sent as a COMMAND_INT.
9MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAMECommand is invalid because a frame is required and the specified frame is not supported.

MAV_MISSION_RESULT

[Enum] Result of mission operation (in a MISSION_ACK message).

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 items exceed 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_PARAM7z / param7 has an invalid value.
13MAV_MISSION_INVALID_SEQUENCEMission item received out of sequence
14MAV_MISSION_DENIEDNot accepting any mission commands from this communication partner.
15MAV_MISSION_OPERATION_CANCELLEDCurrent mission operation cancelled (e.g. mission upload, mission download).

MAV_SEVERITY

[Enum] 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

[Enum] 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

[Enum] 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
100SERIAL_CONTROL_SERIAL0SERIAL0
101SERIAL_CONTROL_SERIAL1SERIAL1
102SERIAL_CONTROL_SERIAL2SERIAL2
103SERIAL_CONTROL_SERIAL3SERIAL3
104SERIAL_CONTROL_SERIAL4SERIAL4
105SERIAL_CONTROL_SERIAL5SERIAL5
106SERIAL_CONTROL_SERIAL6SERIAL6
107SERIAL_CONTROL_SERIAL7SERIAL7
108SERIAL_CONTROL_SERIAL8SERIAL8
109SERIAL_CONTROL_SERIAL9SERIAL9

SERIAL_CONTROL_FLAG

[Enum] 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

[Enum] 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

[Enum] 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

[Enum] 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 the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead.
2MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT

DEPRECATED: Replaced by MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST (2022-03).

Autopilot supports the new param float message type.
4MAV_PROTOCOL_CAPABILITY_MISSION_INTAutopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated).
8MAV_PROTOCOL_CAPABILITY_COMMAND_INTAutopilot supports COMMAND_INT scaled integer message type.
16MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISEParameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported.
32MAV_PROTOCOL_CAPABILITY_FTPAutopilot supports the File Transfer Protocol v1: https://mavlink.io/en/services/ftp.html.
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_RESERVED3Reserved for future use.
2048MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATIONAutopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination).
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_RESERVED2Reserved for future use.
131072MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CASTParameter protocol uses C-cast of parameter values to set the param_value (float) fields: https://mavlink.io/en/services/parameter.html#parameter-encoding. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported.

MAV_MISSION_TYPE

[Enum] 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_NAV_FENCE_ GeoFence items.
2MAV_MISSION_TYPE_RALLYSpecifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items.
255MAV_MISSION_TYPE_ALLOnly used in MISSION_CLEAR_ALL to clear all mission types.

MAV_ESTIMATOR_TYPE

[Enum] Enumeration of estimator types

ValueField NameDescription
0MAV_ESTIMATOR_TYPE_UNKNOWNUnknown type of the estimator.
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.
6MAV_ESTIMATOR_TYPE_MOCAPEstimate from external motion capturing system.
7MAV_ESTIMATOR_TYPE_LIDAREstimator based on lidar sensor input.
8MAV_ESTIMATOR_TYPE_AUTOPILOTEstimator on autopilot.

MAV_BATTERY_TYPE

[Enum] 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

[Enum] 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_FUNCTION_PAYLOADPayload battery

MAV_BATTERY_CHARGE_STATE

[Enum] Enumeration for battery charge 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. Possible causes (faults) are listed in MAV_BATTERY_FAULT.
6MAV_BATTERY_CHARGE_STATE_UNHEALTHYBattery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT.
7MAV_BATTERY_CHARGE_STATE_CHARGINGBattery is charging.

MAV_BATTERY_MODE

[Enum] Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight.

ValueField NameDescription
0MAV_BATTERY_MODE_UNKNOWNBattery mode not supported/unknown battery mode/normal operation.
1MAV_BATTERY_MODE_AUTO_DISCHARGINGBattery is auto discharging (towards storage level).
2MAV_BATTERY_MODE_HOT_SWAPBattery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits).

MAV_BATTERY_FAULT

[Enum] Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set.

ValueField NameDescription
1MAV_BATTERY_FAULT_DEEP_DISCHARGEBattery has deep discharged.
2MAV_BATTERY_FAULT_SPIKESVoltage spikes.
4MAV_BATTERY_FAULT_CELL_FAILOne or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used).
8MAV_BATTERY_FAULT_OVER_CURRENTOver-current fault.
16MAV_BATTERY_FAULT_OVER_TEMPERATUREOver-temperature fault.
32MAV_BATTERY_FAULT_UNDER_TEMPERATUREUnder-temperature fault.
64MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGEVehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
128MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWAREBattery firmware is not compatible with current autopilot firmware.
256BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATIONBattery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s).

MAV_GENERATOR_STATUS_FLAG

[Enum] Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly).

ValueField NameDescription
1MAV_GENERATOR_STATUS_FLAG_OFFGenerator is off.
2MAV_GENERATOR_STATUS_FLAG_READYGenerator is ready to start generating power.
4MAV_GENERATOR_STATUS_FLAG_GENERATINGGenerator is generating power.
8MAV_GENERATOR_STATUS_FLAG_CHARGINGGenerator is charging the batteries (generating enough power to charge and provide the load).
16MAV_GENERATOR_STATUS_FLAG_REDUCED_POWERGenerator is operating at a reduced maximum power.
32MAV_GENERATOR_STATUS_FLAG_MAXPOWERGenerator is providing the maximum output.
64MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNINGGenerator is near the maximum operating temperature, cooling is insufficient.
128MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULTGenerator hit the maximum operating temperature and shutdown.
256MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNINGPower electronics are near the maximum operating temperature, cooling is insufficient.
512MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULTPower electronics hit the maximum operating temperature and shutdown.
1024MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULTPower electronics experienced a fault and shutdown.
2048MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULTThe power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening.
4096MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNINGGenerator controller having communication problems.
8192MAV_GENERATOR_STATUS_FLAG_COOLING_WARNINGPower electronic or generator cooling system error.
16384MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULTGenerator controller power rail experienced a fault.
32768MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULTGenerator controller exceeded the overcurrent threshold and shutdown to prevent damage.
65536MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULTGenerator controller detected a high current going into the batteries and shutdown to prevent battery damage.
131072MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULTGenerator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating.
262144MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULTBatteries are under voltage (generator will not start).
524288MAV_GENERATOR_STATUS_FLAG_START_INHIBITEDGenerator start is inhibited by e.g. a safety switch.
1048576MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIREDGenerator requires maintenance.
2097152MAV_GENERATOR_STATUS_FLAG_WARMING_UPGenerator is not ready to generate yet.
4194304MAV_GENERATOR_STATUS_FLAG_IDLEGenerator is idle.

MAV_VTOL_STATE

[Enum] 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

[Enum] 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

[Enum] 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

[Enum] 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

[Enum] 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
128ADSB_FLAGS_VERTICAL_VELOCITY_VALID
256ADSB_FLAGS_BARO_VALID
32768ADSB_FLAGS_SOURCE_UAT

MAV_DO_REPOSITION_FLAGS

[Enum] 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

SPEED_TYPE

[Enum] Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED

ValueField NameDescription
0SPEED_TYPE_AIRSPEEDAirspeed
1SPEED_TYPE_GROUNDSPEEDGroundspeed
2SPEED_TYPE_CLIMB_SPEEDClimb speed
3SPEED_TYPE_DESCENT_SPEEDDescent speed

ESTIMATOR_STATUS_FLAGS

[Enum] Flags in ESTIMATOR_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

[Enum] Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST.

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

[Enum] Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST.

ValueField NameDescription
0MOTOR_TEST_THROTTLE_PERCENTThrottle as a percentage (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

[Enum]

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

[Enum] 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

[Enum] 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 panicking, and may take actions to avoid threat

MAV_COLLISION_SRC

[Enum] Source of information about this collision.

ValueField NameDescription
0MAV_COLLISION_SRC_ADSBID field references ADSB_VEHICLE packets

GPS_FIX_TYPE

[Enum] 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

[Enum] RTK GPS baseline coordinate system, used for RTK corrections

ValueField NameDescription
0RTK_BASELINE_COORDINATE_SYSTEM_ECEFEarth-centered, Earth-fixed
1RTK_BASELINE_COORDINATE_SYSTEM_NEDRTK basestation centered, north, east, down

LANDING_TARGET_TYPE

[Enum] 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

[Enum] 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

[Enum] 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)
256CAMERA_CAP_FLAGS_HAS_VIDEO_STREAMCamera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)
512CAMERA_CAP_FLAGS_HAS_TRACKING_POINTCamera supports tracking of a point on the camera view.
1024CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLECamera supports tracking of a selection rectangle on the camera view.
2048CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUSCamera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS).

VIDEO_STREAM_STATUS_FLAGS

[Enum] Stream status flags (Bitmap)

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

VIDEO_STREAM_TYPE

[Enum] Video stream types

ValueField NameDescription
0VIDEO_STREAM_TYPE_RTSPStream is RTSP
1VIDEO_STREAM_TYPE_RTPUDPStream is RTP UDP (URI gives the port number)
2VIDEO_STREAM_TYPE_TCP_MPEGStream is MPEG on TCP
3VIDEO_STREAM_TYPE_MPEG_TS_H264Stream is h.264 on MPEG TS (URI gives the port number)

CAMERA_TRACKING_STATUS_FLAGS

[Enum] Camera tracking status flags

ValueField NameDescription
0CAMERA_TRACKING_STATUS_FLAGS_IDLECamera is not tracking
1CAMERA_TRACKING_STATUS_FLAGS_ACTIVECamera is tracking
2CAMERA_TRACKING_STATUS_FLAGS_ERRORCamera tracking in error state

CAMERA_TRACKING_MODE

[Enum] Camera tracking modes

ValueField NameDescription
0CAMERA_TRACKING_MODE_NONENot tracking
1CAMERA_TRACKING_MODE_POINTTarget is a point
2CAMERA_TRACKING_MODE_RECTANGLETarget is a rectangle

CAMERA_TRACKING_TARGET_DATA

[Enum] Camera tracking target data (shows where tracked target is within image)

ValueField NameDescription
0CAMERA_TRACKING_TARGET_DATA_NONENo target data
1CAMERA_TRACKING_TARGET_DATA_EMBEDDEDTarget data embedded in image data (proprietary)
2CAMERA_TRACKING_TARGET_DATA_RENDEREDTarget data rendered in image
4CAMERA_TRACKING_TARGET_DATA_IN_STATUSTarget data within status message (Point or Rectangle)

CAMERA_ZOOM_TYPE

[Enum] 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 percentage value between 0.0 and 100.0)
3ZOOM_TYPE_FOCAL_LENGTHZoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)
4ZOOM_TYPE_HORIZONTAL_FOVZoom value as horizontal field of view in degrees.

SET_FOCUS_TYPE

[Enum] 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_RANGEFocus value as proportion of full camera focus range (a value between 0.0 and 100.0)
3FOCUS_TYPE_METERSFocus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera).
4FOCUS_TYPE_AUTOFocus automatically.
5FOCUS_TYPE_AUTO_SINGLESingle auto focus. Mainly used for still pictures. Usually abbreviated as AF-S.
6FOCUS_TYPE_AUTO_CONTINUOUSContinuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C.

CAMERA_SOURCE

[Enum] Camera sources for MAV_CMD_SET_CAMERA_SOURCE

ValueField NameDescription
0CAMERA_SOURCE_DEFAULTDefault camera source.
1CAMERA_SOURCE_RGBRGB camera source.
2CAMERA_SOURCE_IRIR camera source.
3CAMERA_SOURCE_NDVINDVI camera source.

PARAM_ACK

[Enum] Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).

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 set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent.

CAMERA_MODE

[Enum] 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

[Enum]

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

[Enum] RC type

ValueField NameDescription
0RC_TYPE_SPEKTRUM_DSM2Spektrum DSM2
1RC_TYPE_SPEKTRUM_DSMXSpektrum DSMX

POSITION_TARGET_TYPEMASK

[Enum] 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

ATTITUDE_TARGET_TYPEMASK

[Enum] Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored.

ValueField NameDescription
1ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNOREIgnore body roll rate
2ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNOREIgnore body pitch rate
4ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNOREIgnore body yaw rate
32ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SETUse 3D body thrust setpoint instead of throttle
64ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNOREIgnore throttle
128ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNOREIgnore attitude

UTM_FLIGHT_STATE

[Enum] 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

[Enum] 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.

CELLULAR_STATUS_FLAG

[Enum] These flags encode the cellular network status

ValueField NameDescription
0CELLULAR_STATUS_FLAG_UNKNOWNState unknown or not reportable.
1CELLULAR_STATUS_FLAG_FAILEDModem is unusable
2CELLULAR_STATUS_FLAG_INITIALIZINGModem is being initialized
3CELLULAR_STATUS_FLAG_LOCKEDModem is locked
4CELLULAR_STATUS_FLAG_DISABLEDModem is not enabled and is powered down
5CELLULAR_STATUS_FLAG_DISABLINGModem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state
6CELLULAR_STATUS_FLAG_ENABLINGModem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state
7CELLULAR_STATUS_FLAG_ENABLEDModem is enabled and powered on but not registered with a network provider and not available for data connections
8CELLULAR_STATUS_FLAG_SEARCHINGModem is searching for a network provider to register
9CELLULAR_STATUS_FLAG_REGISTEREDModem is registered with a network provider, and data connections and messaging may be available for use
10CELLULAR_STATUS_FLAG_DISCONNECTINGModem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated
11CELLULAR_STATUS_FLAG_CONNECTINGModem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered
12CELLULAR_STATUS_FLAG_CONNECTEDOne or more packet data bearers is active and connected

CELLULAR_NETWORK_FAILED_REASON

[Enum] These flags are used to diagnose the failure state of CELLULAR_STATUS

ValueField NameDescription
0CELLULAR_NETWORK_FAILED_REASON_NONENo error
1CELLULAR_NETWORK_FAILED_REASON_UNKNOWNError state is unknown
2CELLULAR_NETWORK_FAILED_REASON_SIM_MISSINGSIM is required for the modem but missing
3CELLULAR_NETWORK_FAILED_REASON_SIM_ERRORSIM is available, but not usable for connection

CELLULAR_NETWORK_RADIO_TYPE

[Enum] Cellular network radio type

ValueField NameDescription
0CELLULAR_NETWORK_RADIO_TYPE_NONE
1CELLULAR_NETWORK_RADIO_TYPE_GSM
2CELLULAR_NETWORK_RADIO_TYPE_CDMA
3CELLULAR_NETWORK_RADIO_TYPE_WCDMA
4CELLULAR_NETWORK_RADIO_TYPE_LTE

PRECISION_LAND_MODE

[Enum] Precision land modes (used in MAV_CMD_NAV_LAND).

ValueField NameDescription
0PRECISION_LAND_MODE_DISABLEDNormal (non-precision) landing.
1PRECISION_LAND_MODE_OPPORTUNISTICUse precision landing if beacon detected when land command accepted, otherwise land normally.
2PRECISION_LAND_MODE_REQUIREDUse precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found).

PARACHUTE_ACTION

[Enum] Parachute actions. Trigger release and enable/disable auto-release.

ValueField NameDescription
0PARACHUTE_DISABLEDisable auto-release of parachute (i.e. release triggered by crash detectors).
1PARACHUTE_ENABLEEnable auto-release of parachute.
2PARACHUTE_RELEASERelease parachute and kill motors.

MAV_TUNNEL_PAYLOAD_TYPE

[Enum]

ValueField NameDescription
0MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWNEncoding of payload unknown.
200MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0Registered for STorM32 gimbal controller.
201MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1Registered for STorM32 gimbal controller.
202MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2Registered for STorM32 gimbal controller.
203MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3Registered for STorM32 gimbal controller.
204MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4Registered for STorM32 gimbal controller.
205MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5Registered for STorM32 gimbal controller.
206MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6Registered for STorM32 gimbal controller.
207MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7Registered for STorM32 gimbal controller.
208MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8Registered for STorM32 gimbal controller.
209MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9Registered for STorM32 gimbal controller.

MAV_ODID_ID_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_ID_TYPE_NONENo type defined.
1MAV_ODID_ID_TYPE_SERIAL_NUMBERManufacturer Serial Number (ANSI/CTA-2063 format).
2MAV_ODID_ID_TYPE_CAA_REGISTRATION_IDCAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID].
3MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUIDUTM (Unmanned Traffic Management) assigned UUID (RFC4122).
4MAV_ODID_ID_TYPE_SPECIFIC_SESSION_IDA 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO.

MAV_ODID_UA_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_UA_TYPE_NONENo UA (Unmanned Aircraft) type defined.
1MAV_ODID_UA_TYPE_AEROPLANEAeroplane/Airplane. Fixed wing.
2MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTORHelicopter or multirotor.
3MAV_ODID_UA_TYPE_GYROPLANEGyroplane.
4MAV_ODID_UA_TYPE_HYBRID_LIFTVTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically.
5MAV_ODID_UA_TYPE_ORNITHOPTEROrnithopter.
6MAV_ODID_UA_TYPE_GLIDERGlider.
7MAV_ODID_UA_TYPE_KITEKite.
8MAV_ODID_UA_TYPE_FREE_BALLOONFree Balloon.
9MAV_ODID_UA_TYPE_CAPTIVE_BALLOONCaptive Balloon.
10MAV_ODID_UA_TYPE_AIRSHIPAirship. E.g. a blimp.
11MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTEFree Fall/Parachute (unpowered).
12MAV_ODID_UA_TYPE_ROCKETRocket.
13MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFTTethered powered aircraft.
14MAV_ODID_UA_TYPE_GROUND_OBSTACLEGround Obstacle.
15MAV_ODID_UA_TYPE_OTHEROther type of aircraft not listed earlier.

MAV_ODID_STATUS

[Enum]

ValueField NameDescription
0MAV_ODID_STATUS_UNDECLAREDThe status of the (UA) Unmanned Aircraft is undefined.
1MAV_ODID_STATUS_GROUNDThe UA is on the ground.
2MAV_ODID_STATUS_AIRBORNEThe UA is in the air.
3MAV_ODID_STATUS_EMERGENCYThe UA is having an emergency.
4MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILUREThe remote ID system is failing or unreliable in some way.

MAV_ODID_HEIGHT_REF

[Enum]

ValueField NameDescription
0MAV_ODID_HEIGHT_REF_OVER_TAKEOFFThe height field is relative to the take-off location.
1MAV_ODID_HEIGHT_REF_OVER_GROUNDThe height field is relative to ground.

MAV_ODID_HOR_ACC

[Enum]

ValueField NameDescription
0MAV_ODID_HOR_ACC_UNKNOWNThe horizontal accuracy is unknown.
1MAV_ODID_HOR_ACC_10NMThe horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km.
2MAV_ODID_HOR_ACC_4NMThe horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km.
3MAV_ODID_HOR_ACC_2NMThe horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km.
4MAV_ODID_HOR_ACC_1NMThe horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km.
5MAV_ODID_HOR_ACC_0_5NMThe horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m.
6MAV_ODID_HOR_ACC_0_3NMThe horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m.
7MAV_ODID_HOR_ACC_0_1NMThe horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m.
8MAV_ODID_HOR_ACC_0_05NMThe horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m.
9MAV_ODID_HOR_ACC_30_METERThe horizontal accuracy is smaller than 30 meter.
10MAV_ODID_HOR_ACC_10_METERThe horizontal accuracy is smaller than 10 meter.
11MAV_ODID_HOR_ACC_3_METERThe horizontal accuracy is smaller than 3 meter.
12MAV_ODID_HOR_ACC_1_METERThe horizontal accuracy is smaller than 1 meter.

MAV_ODID_VER_ACC

[Enum]

ValueField NameDescription
0MAV_ODID_VER_ACC_UNKNOWNThe vertical accuracy is unknown.
1MAV_ODID_VER_ACC_150_METERThe vertical accuracy is smaller than 150 meter.
2MAV_ODID_VER_ACC_45_METERThe vertical accuracy is smaller than 45 meter.
3MAV_ODID_VER_ACC_25_METERThe vertical accuracy is smaller than 25 meter.
4MAV_ODID_VER_ACC_10_METERThe vertical accuracy is smaller than 10 meter.
5MAV_ODID_VER_ACC_3_METERThe vertical accuracy is smaller than 3 meter.
6MAV_ODID_VER_ACC_1_METERThe vertical accuracy is smaller than 1 meter.

MAV_ODID_SPEED_ACC

[Enum]

ValueField NameDescription
0MAV_ODID_SPEED_ACC_UNKNOWNThe speed accuracy is unknown.
1MAV_ODID_SPEED_ACC_10_METERS_PER_SECONDThe speed accuracy is smaller than 10 meters per second.
2MAV_ODID_SPEED_ACC_3_METERS_PER_SECONDThe speed accuracy is smaller than 3 meters per second.
3MAV_ODID_SPEED_ACC_1_METERS_PER_SECONDThe speed accuracy is smaller than 1 meters per second.
4MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECONDThe speed accuracy is smaller than 0.3 meters per second.

MAV_ODID_TIME_ACC

[Enum]

ValueField NameDescription
0MAV_ODID_TIME_ACC_UNKNOWNThe timestamp accuracy is unknown.
1MAV_ODID_TIME_ACC_0_1_SECONDThe timestamp accuracy is smaller than or equal to 0.1 second.
2MAV_ODID_TIME_ACC_0_2_SECONDThe timestamp accuracy is smaller than or equal to 0.2 second.
3MAV_ODID_TIME_ACC_0_3_SECONDThe timestamp accuracy is smaller than or equal to 0.3 second.
4MAV_ODID_TIME_ACC_0_4_SECONDThe timestamp accuracy is smaller than or equal to 0.4 second.
5MAV_ODID_TIME_ACC_0_5_SECONDThe timestamp accuracy is smaller than or equal to 0.5 second.
6MAV_ODID_TIME_ACC_0_6_SECONDThe timestamp accuracy is smaller than or equal to 0.6 second.
7MAV_ODID_TIME_ACC_0_7_SECONDThe timestamp accuracy is smaller than or equal to 0.7 second.
8MAV_ODID_TIME_ACC_0_8_SECONDThe timestamp accuracy is smaller than or equal to 0.8 second.
9MAV_ODID_TIME_ACC_0_9_SECONDThe timestamp accuracy is smaller than or equal to 0.9 second.
10MAV_ODID_TIME_ACC_1_0_SECONDThe timestamp accuracy is smaller than or equal to 1.0 second.
11MAV_ODID_TIME_ACC_1_1_SECONDThe timestamp accuracy is smaller than or equal to 1.1 second.
12MAV_ODID_TIME_ACC_1_2_SECONDThe timestamp accuracy is smaller than or equal to 1.2 second.
13MAV_ODID_TIME_ACC_1_3_SECONDThe timestamp accuracy is smaller than or equal to 1.3 second.
14MAV_ODID_TIME_ACC_1_4_SECONDThe timestamp accuracy is smaller than or equal to 1.4 second.
15MAV_ODID_TIME_ACC_1_5_SECONDThe timestamp accuracy is smaller than or equal to 1.5 second.

MAV_ODID_AUTH_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_AUTH_TYPE_NONENo authentication type is specified.
1MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURESignature for the UAS (Unmanned Aircraft System) ID.
2MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURESignature for the Operator ID.
3MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURESignature for the entire message set.
4MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_IDAuthentication is provided by Network Remote ID.
5MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATIONThe exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO.

MAV_ODID_DESC_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_DESC_TYPE_TEXTOptional free-form text description of the purpose of the flight.
1MAV_ODID_DESC_TYPE_EMERGENCYOptional additional clarification when status == MAV_ODID_STATUS_EMERGENCY.
2MAV_ODID_DESC_TYPE_EXTENDED_STATUSOptional additional clarification when status != MAV_ODID_STATUS_EMERGENCY.

MAV_ODID_OPERATOR_LOCATION_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFFThe location/altitude of the operator is the same as the take-off location.
1MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSSThe location/altitude of the operator is dynamic. E.g. based on live GNSS data.
2MAV_ODID_OPERATOR_LOCATION_TYPE_FIXEDThe location/altitude of the operator are fixed values.

MAV_ODID_CLASSIFICATION_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_CLASSIFICATION_TYPE_UNDECLAREDThe classification type for the UA is undeclared.
1MAV_ODID_CLASSIFICATION_TYPE_EUThe classification type for the UA follows EU (European Union) specifications.

MAV_ODID_CATEGORY_EU

[Enum]

ValueField NameDescription
0MAV_ODID_CATEGORY_EU_UNDECLAREDThe category for the UA, according to the EU specification, is undeclared.
1MAV_ODID_CATEGORY_EU_OPENThe category for the UA, according to the EU specification, is the Open category.
2MAV_ODID_CATEGORY_EU_SPECIFICThe category for the UA, according to the EU specification, is the Specific category.
3MAV_ODID_CATEGORY_EU_CERTIFIEDThe category for the UA, according to the EU specification, is the Certified category.

MAV_ODID_CLASS_EU

[Enum]

ValueField NameDescription
0MAV_ODID_CLASS_EU_UNDECLAREDThe class for the UA, according to the EU specification, is undeclared.
1MAV_ODID_CLASS_EU_CLASS_0The class for the UA, according to the EU specification, is Class 0.
2MAV_ODID_CLASS_EU_CLASS_1The class for the UA, according to the EU specification, is Class 1.
3MAV_ODID_CLASS_EU_CLASS_2The class for the UA, according to the EU specification, is Class 2.
4MAV_ODID_CLASS_EU_CLASS_3The class for the UA, according to the EU specification, is Class 3.
5MAV_ODID_CLASS_EU_CLASS_4The class for the UA, according to the EU specification, is Class 4.
6MAV_ODID_CLASS_EU_CLASS_5The class for the UA, according to the EU specification, is Class 5.
7MAV_ODID_CLASS_EU_CLASS_6The class for the UA, according to the EU specification, is Class 6.

MAV_ODID_OPERATOR_ID_TYPE

[Enum]

ValueField NameDescription
0MAV_ODID_OPERATOR_ID_TYPE_CAACAA (Civil Aviation Authority) registered operator ID.

MAV_ODID_ARM_STATUS

[Enum]

ValueField NameDescription
0MAV_ODID_ARM_STATUS_GOOD_TO_ARMPassing arming checks.
1MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERICGeneric arming failure, see error string for details.

TUNE_FORMAT

[Enum] Tune formats (used for vehicle buzzer/tone generation).

ValueField NameDescription
1TUNE_FORMAT_QBASIC1_1Format is QBasic 1.1 Play: https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm.
2TUNE_FORMAT_MML_MODERNFormat is Modern Music Markup Language (MML): https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML.

AIS_TYPE

[Enum] Type of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

ValueField NameDescription
0AIS_TYPE_UNKNOWNNot available (default).
1AIS_TYPE_RESERVED_1
2AIS_TYPE_RESERVED_2
3AIS_TYPE_RESERVED_3
4AIS_TYPE_RESERVED_4
5AIS_TYPE_RESERVED_5
6AIS_TYPE_RESERVED_6
7AIS_TYPE_RESERVED_7
8AIS_TYPE_RESERVED_8
9AIS_TYPE_RESERVED_9
10AIS_TYPE_RESERVED_10
11AIS_TYPE_RESERVED_11
12AIS_TYPE_RESERVED_12
13AIS_TYPE_RESERVED_13
14AIS_TYPE_RESERVED_14
15AIS_TYPE_RESERVED_15
16AIS_TYPE_RESERVED_16
17AIS_TYPE_RESERVED_17
18AIS_TYPE_RESERVED_18
19AIS_TYPE_RESERVED_19
20AIS_TYPE_WIGWing In Ground effect.
21AIS_TYPE_WIG_HAZARDOUS_A
22AIS_TYPE_WIG_HAZARDOUS_B
23AIS_TYPE_WIG_HAZARDOUS_C
24AIS_TYPE_WIG_HAZARDOUS_D
25AIS_TYPE_WIG_RESERVED_1
26AIS_TYPE_WIG_RESERVED_2
27AIS_TYPE_WIG_RESERVED_3
28AIS_TYPE_WIG_RESERVED_4
29AIS_TYPE_WIG_RESERVED_5
30AIS_TYPE_FISHING
31AIS_TYPE_TOWING
32AIS_TYPE_TOWING_LARGETowing: length exceeds 200m or breadth exceeds 25m.
33AIS_TYPE_DREDGINGDredging or other underwater ops.
34AIS_TYPE_DIVING
35AIS_TYPE_MILITARY
36AIS_TYPE_SAILING
37AIS_TYPE_PLEASURE
38AIS_TYPE_RESERVED_20
39AIS_TYPE_RESERVED_21
40AIS_TYPE_HSCHigh Speed Craft.
41AIS_TYPE_HSC_HAZARDOUS_A
42AIS_TYPE_HSC_HAZARDOUS_B
43AIS_TYPE_HSC_HAZARDOUS_C
44AIS_TYPE_HSC_HAZARDOUS_D
45AIS_TYPE_HSC_RESERVED_1
46AIS_TYPE_HSC_RESERVED_2
47AIS_TYPE_HSC_RESERVED_3
48AIS_TYPE_HSC_RESERVED_4
49AIS_TYPE_HSC_UNKNOWN
50AIS_TYPE_PILOT
51AIS_TYPE_SARSearch And Rescue vessel.
52AIS_TYPE_TUG
53AIS_TYPE_PORT_TENDER
54AIS_TYPE_ANTI_POLLUTIONAnti-pollution equipment.
55AIS_TYPE_LAW_ENFORCEMENT
56AIS_TYPE_SPARE_LOCAL_1
57AIS_TYPE_SPARE_LOCAL_2
58AIS_TYPE_MEDICAL_TRANSPORT
59AIS_TYPE_NONECOMBATANTNoncombatant ship according to RR Resolution No. 18.
60AIS_TYPE_PASSENGER
61AIS_TYPE_PASSENGER_HAZARDOUS_A
62AIS_TYPE_PASSENGER_HAZARDOUS_B
63AIS_TYPE_PASSENGER_HAZARDOUS_C
64AIS_TYPE_PASSENGER_HAZARDOUS_D
65AIS_TYPE_PASSENGER_RESERVED_1
66AIS_TYPE_PASSENGER_RESERVED_2
67AIS_TYPE_PASSENGER_RESERVED_3
68AIS_TYPE_PASSENGER_RESERVED_4
69AIS_TYPE_PASSENGER_UNKNOWN
70AIS_TYPE_CARGO
71AIS_TYPE_CARGO_HAZARDOUS_A
72AIS_TYPE_CARGO_HAZARDOUS_B
73AIS_TYPE_CARGO_HAZARDOUS_C
74AIS_TYPE_CARGO_HAZARDOUS_D
75AIS_TYPE_CARGO_RESERVED_1
76AIS_TYPE_CARGO_RESERVED_2
77AIS_TYPE_CARGO_RESERVED_3
78AIS_TYPE_CARGO_RESERVED_4
79AIS_TYPE_CARGO_UNKNOWN
80AIS_TYPE_TANKER
81AIS_TYPE_TANKER_HAZARDOUS_A
82AIS_TYPE_TANKER_HAZARDOUS_B
83AIS_TYPE_TANKER_HAZARDOUS_C
84AIS_TYPE_TANKER_HAZARDOUS_D
85AIS_TYPE_TANKER_RESERVED_1
86AIS_TYPE_TANKER_RESERVED_2
87AIS_TYPE_TANKER_RESERVED_3
88AIS_TYPE_TANKER_RESERVED_4
89AIS_TYPE_TANKER_UNKNOWN
90AIS_TYPE_OTHER
91AIS_TYPE_OTHER_HAZARDOUS_A
92AIS_TYPE_OTHER_HAZARDOUS_B
93AIS_TYPE_OTHER_HAZARDOUS_C
94AIS_TYPE_OTHER_HAZARDOUS_D
95AIS_TYPE_OTHER_RESERVED_1
96AIS_TYPE_OTHER_RESERVED_2
97AIS_TYPE_OTHER_RESERVED_3
98AIS_TYPE_OTHER_RESERVED_4
99AIS_TYPE_OTHER_UNKNOWN

AIS_NAV_STATUS

[Enum] Navigational status of AIS vessel, enum duplicated from AIS standard, https://gpsd.gitlab.io/gpsd/AIVDM.html

ValueField NameDescription
0UNDER_WAYUnder way using engine.
1AIS_NAV_ANCHORED
2AIS_NAV_UN_COMMANDED
3AIS_NAV_RESTRICTED_MANOEUVERABILITY
4AIS_NAV_DRAUGHT_CONSTRAINED
5AIS_NAV_MOORED
6AIS_NAV_AGROUND
7AIS_NAV_FISHING
8AIS_NAV_SAILING
9AIS_NAV_RESERVED_HSC
10AIS_NAV_RESERVED_WIG
11AIS_NAV_RESERVED_1
12AIS_NAV_RESERVED_2
13AIS_NAV_RESERVED_3
14AIS_NAV_AIS_SARTSearch And Rescue Transponder.
15AIS_NAV_UNKNOWNNot available (default).

AIS_FLAGS

[Enum] These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid.

ValueField NameDescription
1AIS_FLAGS_POSITION_ACCURACY1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m.
2AIS_FLAGS_VALID_COG
4AIS_FLAGS_VALID_VELOCITY
8AIS_FLAGS_HIGH_VELOCITY1 = Velocity over 52.5765m/s (102.2 knots)
16AIS_FLAGS_VALID_TURN_RATE
32AIS_FLAGS_TURN_RATE_SIGN_ONLYOnly the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s
64AIS_FLAGS_VALID_DIMENSIONS
128AIS_FLAGS_LARGE_BOW_DIMENSIONDistance to bow is larger than 511m
256AIS_FLAGS_LARGE_STERN_DIMENSIONDistance to stern is larger than 511m
512AIS_FLAGS_LARGE_PORT_DIMENSIONDistance to port side is larger than 63m
1024AIS_FLAGS_LARGE_STARBOARD_DIMENSIONDistance to starboard side is larger than 63m
2048AIS_FLAGS_VALID_CALLSIGN
4096AIS_FLAGS_VALID_NAME

FAILURE_UNIT

[Enum] List of possible units where failures can be injected.

ValueField NameDescription
0FAILURE_UNIT_SENSOR_GYRO
1FAILURE_UNIT_SENSOR_ACCEL
2FAILURE_UNIT_SENSOR_MAG
3FAILURE_UNIT_SENSOR_BARO
4FAILURE_UNIT_SENSOR_GPS
5FAILURE_UNIT_SENSOR_OPTICAL_FLOW
6FAILURE_UNIT_SENSOR_VIO
7FAILURE_UNIT_SENSOR_DISTANCE_SENSOR
8FAILURE_UNIT_SENSOR_AIRSPEED
100FAILURE_UNIT_SYSTEM_BATTERY
101FAILURE_UNIT_SYSTEM_MOTOR
102FAILURE_UNIT_SYSTEM_SERVO
103FAILURE_UNIT_SYSTEM_AVOIDANCE
104FAILURE_UNIT_SYSTEM_RC_SIGNAL

FAILURE_TYPE

[Enum] List of possible failure type to inject.

ValueField NameDescription
0FAILURE_TYPE_OKNo failure injected, used to reset a previous failure.
1FAILURE_TYPE_OFFSets unit off, so completely non-responsive.
2FAILURE_TYPE_STUCKUnit is stuck e.g. keeps reporting the same value.
3FAILURE_TYPE_GARBAGEUnit is reporting complete garbage.
4FAILURE_TYPE_WRONGUnit is consistently wrong.
5FAILURE_TYPE_SLOWUnit is slow, so e.g. reporting at slower than expected rate.
6FAILURE_TYPE_DELAYEDData of unit is delayed in time.
7FAILURE_TYPE_INTERMITTENTUnit is sometimes working, sometimes not.

[Enum]

ValueField NameDescription

MAV_WINCH_STATUS_FLAG

[Enum] Winch status flags used in WINCH_STATUS

ValueField NameDescription
1MAV_WINCH_STATUS_HEALTHYWinch is healthy
2MAV_WINCH_STATUS_FULLY_RETRACTEDWinch line is fully retracted
4MAV_WINCH_STATUS_MOVINGWinch motor is moving
8MAV_WINCH_STATUS_CLUTCH_ENGAGEDWinch clutch is engaged allowing motor to move freely.
16MAV_WINCH_STATUS_LOCKEDWinch is locked by locking mechanism.
32MAV_WINCH_STATUS_DROPPINGWinch is gravity dropping payload.
64MAV_WINCH_STATUS_ARRESTINGWinch is arresting payload descent.
128MAV_WINCH_STATUS_GROUND_SENSEWinch is using torque measurements to sense the ground.
256MAV_WINCH_STATUS_RETRACTINGWinch is returning to the fully retracted position.
512MAV_WINCH_STATUS_REDELIVERWinch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING.
1024MAV_WINCH_STATUS_ABANDON_LINEWinch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold.
2048MAV_WINCH_STATUS_LOCKINGWinch is engaging the locking mechanism.
4096MAV_WINCH_STATUS_LOAD_LINEWinch is spooling on line.
8192MAV_WINCH_STATUS_LOAD_PAYLOADWinch is loading a payload.

MAG_CAL_STATUS

[Enum]

ValueField NameDescription
0MAG_CAL_NOT_STARTED
1MAG_CAL_WAITING_TO_START
2MAG_CAL_RUNNING_STEP_ONE
3MAG_CAL_RUNNING_STEP_TWO
4MAG_CAL_SUCCESS
5MAG_CAL_FAILED
6MAG_CAL_BAD_ORIENTATION
7MAG_CAL_BAD_RADIUS

MAV_EVENT_ERROR_REASON

[Enum] Reason for an event error response.

ValueField NameDescription
0MAV_EVENT_ERROR_REASON_UNAVAILABLEThe requested event is not available (anymore).

MAV_EVENT_CURRENT_SEQUENCE_FLAGS

[Enum] Flags for CURRENT_EVENT_SEQUENCE.

ValueField NameDescription
1MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESETA sequence reset has happened (e.g. vehicle reboot).

HIL_SENSOR_UPDATED_FLAGS

[Enum] Flags in the HIL_SENSOR message indicate which fields have updated since the last message

ValueField NameDescription
0HIL_SENSOR_UPDATED_NONENone of the fields in HIL_SENSOR have been updated
1HIL_SENSOR_UPDATED_XACCThe value in the xacc field has been updated
2HIL_SENSOR_UPDATED_YACCThe value in the yacc field has been updated
4HIL_SENSOR_UPDATED_ZACCThe value in the zacc field has been updated
8HIL_SENSOR_UPDATED_XGYROThe value in the xgyro field has been updated
16HIL_SENSOR_UPDATED_YGYROThe value in the ygyro field has been updated
32HIL_SENSOR_UPDATED_ZGYROThe value in the zgyro field has been updated
64HIL_SENSOR_UPDATED_XMAGThe value in the xmag field has been updated
128HIL_SENSOR_UPDATED_YMAGThe value in the ymag field has been updated
256HIL_SENSOR_UPDATED_ZMAGThe value in the zmag field has been updated
512HIL_SENSOR_UPDATED_ABS_PRESSUREThe value in the abs_pressure field has been updated
1024HIL_SENSOR_UPDATED_DIFF_PRESSUREThe value in the diff_pressure field has been updated
2048HIL_SENSOR_UPDATED_PRESSURE_ALTThe value in the pressure_alt field has been updated
4096HIL_SENSOR_UPDATED_TEMPERATUREThe value in the temperature field has been updated
2147483648HIL_SENSOR_UPDATED_RESETFull reset of attitude/position/velocities/etc was performed in sim (Bit 31).

HIGHRES_IMU_UPDATED_FLAGS

[Enum] Flags in the HIGHRES_IMU message indicate which fields have updated since the last message

ValueField NameDescription
0HIGHRES_IMU_UPDATED_NONENone of the fields in HIGHRES_IMU have been updated
1HIGHRES_IMU_UPDATED_XACCThe value in the xacc field has been updated
2HIGHRES_IMU_UPDATED_YACCThe value in the yacc field has been updated
4HIGHRES_IMU_UPDATED_ZACCThe value in the zacc field has been updated since
8HIGHRES_IMU_UPDATED_XGYROThe value in the xgyro field has been updated
16HIGHRES_IMU_UPDATED_YGYROThe value in the ygyro field has been updated
32HIGHRES_IMU_UPDATED_ZGYROThe value in the zgyro field has been updated
64HIGHRES_IMU_UPDATED_XMAGThe value in the xmag field has been updated
128HIGHRES_IMU_UPDATED_YMAGThe value in the ymag field has been updated
256HIGHRES_IMU_UPDATED_ZMAGThe value in the zmag field has been updated
512HIGHRES_IMU_UPDATED_ABS_PRESSUREThe value in the abs_pressure field has been updated
1024HIGHRES_IMU_UPDATED_DIFF_PRESSUREThe value in the diff_pressure field has been updated
2048HIGHRES_IMU_UPDATED_PRESSURE_ALTThe value in the pressure_alt field has been updated
4096HIGHRES_IMU_UPDATED_TEMPERATUREThe value in the temperature field has been updated
65535HIGHRES_IMU_UPDATED_ALLAll fields in HIGHRES_IMU have been updated.

CAN_FILTER_OP

[Enum]

ValueField NameDescription
0CAN_FILTER_REPLACE
1CAN_FILTER_ADD
2CAN_FILTER_REMOVE

MAV_FTP_ERR

[Enum] MAV FTP error codes (https://mavlink.io/en/services/ftp.html)

ValueField NameDescription
0MAV_FTP_ERR_NONENone: No error
1MAV_FTP_ERR_FAILFail: Unknown failure
2MAV_FTP_ERR_FAILERRNOFailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. This is a file-system error number understood by the server operating system.
3MAV_FTP_ERR_INVALIDDATASIZEInvalidDataSize: Payload size is invalid
4MAV_FTP_ERR_INVALIDSESSIONInvalidSession: Session is not currently open
5MAV_FTP_ERR_NOSESSIONSAVAILABLENoSessionsAvailable: All available sessions are already in use
6MAV_FTP_ERR_EOFEOF: Offset past end of file for ListDirectory and ReadFile commands
7MAV_FTP_ERR_UNKNOWNCOMMANDUnknownCommand: Unknown command / opcode
8MAV_FTP_ERR_FILEEXISTSFileExists: File/directory already exists
9MAV_FTP_ERR_FILEPROTECTEDFileProtected: File/directory is write protected
10MAV_FTP_ERR_FILENOTFOUNDFileNotFound: File/directory not found

MAV_FTP_OPCODE

[Enum] MAV FTP opcodes: https://mavlink.io/en/services/ftp.html

ValueField NameDescription
0MAV_FTP_OPCODE_NONENone. Ignored, always ACKed
1MAV_FTP_OPCODE_TERMINATESESSIONTerminateSession: Terminates open Read session
2MAV_FTP_OPCODE_RESETSESSIONResetSessions: Terminates all open read sessions
3MAV_FTP_OPCODE_LISTDIRECTORYListDirectory. List files and directories in path from offset
4MAV_FTP_OPCODE_OPENFILEROOpenFileRO: Opens file at path for reading, returns session
5MAV_FTP_OPCODE_READFILEReadFile: Reads size bytes from offset in session
6MAV_FTP_OPCODE_CREATEFILECreateFile: Creates file at path for writing, returns session
7MAV_FTP_OPCODE_WRITEFILEWriteFile: Writes size bytes to offset in session
8MAV_FTP_OPCODE_REMOVEFILERemoveFile: Remove file at path
9MAV_FTP_OPCODE_CREATEDIRECTORYCreateDirectory: Creates directory at path
10MAV_FTP_OPCODE_REMOVEDIRECTORYRemoveDirectory: Removes directory at path. The directory must be empty.
11MAV_FTP_OPCODE_OPENFILEWOOpenFileWO: Opens file at path for writing, returns session
12MAV_FTP_OPCODE_TRUNCATEFILETruncateFile: Truncate file at path to offset length
13MAV_FTP_OPCODE_RENAMERename: Rename path1 to path2
14MAV_FTP_OPCODE_CALCFILECRCCalcFileCRC32: Calculate CRC32 for file at path
15MAV_FTP_OPCODE_BURSTREADFILEBurstReadFile: Burst download session file
128MAV_FTP_OPCODE_ACKACK: ACK response
129MAV_FTP_OPCODE_NAKNAK: NAK response

MISSION_STATE

[Enum] States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles.

ValueField NameDescription
0MISSION_STATE_UNKNOWNThe mission status reporting is not supported.
1MISSION_STATE_NO_MISSIONNo mission on the vehicle.
2MISSION_STATE_NOT_STARTEDMission has not started. This is the case after a mission has uploaded but not yet started executing.
3MISSION_STATE_ACTIVEMission is active, and will execute mission items when in auto mode.
4MISSION_STATE_PAUSEDMission is paused when in auto mode.
5MISSION_STATE_COMPLETEMission has executed all mission items.

SAFETY_SWITCH_STATE

[Enum] Possible safety switch states.

ValueField NameDescription
0SAFETY_SWITCH_STATE_SAFESafety switch is engaged and vehicle should be safe to approach.
1SAFETY_SWITCH_STATE_DANGEROUSSafety switch is NOT engaged and motors, propellers and other actuators should be considered active.

MAVLink Commands (MAV_CMD)

MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.

Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries

MAV_CMD_NAV_WAYPOINT (16 )

[Command] Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION).

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: HoldHold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)min:0s
2: Accept RadiusAcceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)min:0m
3: Pass Radius0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.m
4: YawDesired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_LOITER_UNLIM (17 )

[Command] Loiter around this waypoint an unlimited amount of time

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1Empty
2Empty
3: RadiusLoiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwisem
4: YawDesired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_LOITER_TURNS (18 )

[Command] Loiter around this waypoint for X turns

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: TurnsNumber of turns.min:0
2: Heading RequiredLeave loiter circle only once heading towards the next waypoint (0 = False)min:0 max:1 increment:1
3: RadiusLoiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwisem
4: Xtrack LocationLoiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_LOITER_TIME (19 )

[Command] Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: TimeLoiter time (only starts once Lat, Lon and Alt is reached).min:0s
2: Heading RequiredLeave loiter circle only once heading towards the next waypoint (0 = False)min:0 max:1 increment:1
3: RadiusLoiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.m
4: Xtrack LocationLoiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_RETURN_TO_LAUNCH (20 )

[Command] Return to launch location

Param (:Label)Description
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_NAV_LAND (21 )

[Command] Land at location.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Abort AltMinimum target altitude if landing is aborted (0 = undefined/use system default).m
2: Land ModePrecision land mode.PRECISION_LAND_MODE
3Empty.
4: Yaw AngleDesired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude.
6: LongitudeLongitude.
7: AltitudeLanding altitude (ground level in current frame).m

MAV_CMD_NAV_TAKEOFF (22 )

[Command] Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: PitchMinimum pitch (if airspeed sensor present), desired pitch without sensordeg
2Empty
3Empty
4: YawYaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_LAND_LOCAL (23 )

[Command] Land at local position (local frame only)

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: TargetLanding target number (if available)min:0 increment:1
2: OffsetMaximum accepted offset from desired landing position - 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 landmin:0m
3: Descend RateLanding descend ratem/s
4: YawDesired yaw anglerad
5: Y PositionY-axis positionm
6: X PositionX-axis positionm
7: Z PositionZ-axis / ground level positionm

MAV_CMD_NAV_TAKEOFF_LOCAL (24 )

[Command] Takeoff from local position (local frame only)

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: PitchMinimum pitch (if airspeed sensor present), desired pitch without sensorrad
2Empty
3: Ascend RateTakeoff ascend ratem/s
4: YawYaw angle (if magnetometer or another yaw estimation source present), ignored without one of theserad
5: Y PositionY-axis positionm
6: X PositionX-axis positionm
7: Z PositionZ-axis positionm

MAV_CMD_NAV_FOLLOW (25 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: FollowingFollowing logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementationincrement:1
2: Ground SpeedGround speed of vehicle to be followedm/s
3: RadiusRadius around waypoint. If positive loiter clockwise, else counter-clockwisem
4: YawDesired yaw angle.deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT (30 )

[Command] 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: ActionClimb 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.min:0 max:2 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7: AltitudeDesired altitudem

MAV_CMD_NAV_LOITER_TO_ALT (31 )

[Command] 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Heading RequiredLeave loiter circle only once heading towards the next waypoint (0 = False)min:0 max:1 increment:1
2: RadiusLoiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.m
3Empty
4: Xtrack LocationLoiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.min:0 max:1 increment:1
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_DO_FOLLOW (32 )

[Command] Begin following a target

Param (:Label)DescriptionValuesUnits
1: System IDSystem ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.min:0 max:255 increment:1
2Reserved
3Reserved
4: Altitude ModeAltitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.min:0 max:2 increment:1
5: AltitudeAltitude above home. (used if mode=2)m
6Reserved
7: Time to LandTime to land in which the MAV should go to the default position hold mode after a message RX timeout.min:0s

MAV_CMD_DO_FOLLOW_REPOSITION (33 )

[Command] Reposition the MAV after a follow target command has been sent

Param (:Label)DescriptionUnits
1: Camera Q1Camera q1 (where 0 is on the ray from the camera to the tracking device)
2: Camera Q2Camera q2
3: Camera Q3Camera q3
4: Camera Q4Camera q4
5: Altitude Offsetaltitude offset from targetm
6: X OffsetX offset from targetm
7: Y OffsetY offset from targetm

MAV_CMD_DO_ORBIT (34 )

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

[Command] Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: RadiusRadius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting.m
2: VelocityTangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting.m/s
3: Yaw BehaviorYaw behavior of the vehicle.ORBIT_YAW_BEHAVIOUR
4: OrbitsOrbit around the centre point for this many radians (i.e. for a three-quarter orbit set 270*Pi/180). 0: Orbit forever. NaN: Use vehicle default, or current value if already orbiting.min:0rad
5: Latitude/XCenter point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.
6: Longitude/YCenter point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.
7: Altitude/ZCenter point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude.

MAV_CMD_NAV_ROI (80 )

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

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValues
1: ROI ModeRegion of interest mode.MAV_ROI
2: WP IndexWaypoint index/ target ID. (see MAV_ROI enum)min:0 increment:1
3: ROI IndexROI index (allows a vehicle to manage multiple ROI's)min:0 increment:1
4Empty
5: Xx the location of the fixed ROI (see MAV_FRAME)
6: Yy
7: Zz

MAV_CMD_NAV_PATHPLANNING (81 )

[Command] Control autonomous path planning on the MAV.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Local Ctrl0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planningmin:0 max:2 increment:1
2: Global Ctrl0: 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 gridmin:0 max:3 increment:1
3Empty
4: YawYaw angle at goaldeg
5: Latitude/XLatitude/X of goal
6: Longitude/YLongitude/Y of goal
7: Altitude/ZAltitude/Z of goal

MAV_CMD_NAV_SPLINE_WAYPOINT (82 )

[Command] Navigate to waypoint using a spline path.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: HoldHold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)min:0s
2Empty
3Empty
4Empty
5: Latitude/XLatitude/X of goal
6: Longitude/YLongitude/Y of goal
7: Altitude/ZAltitude/Z of goal

MAV_CMD_NAV_VTOL_TAKEOFF (84 )

[Command] Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.).

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1Empty
2: Transition HeadingFront transition heading.VTOL_TRANSITION_HEADING
3Empty
4: Yaw AngleYaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_VTOL_LAND (85 )

[Command] Land using VTOL mode

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Land OptionsLanding behaviour.NAV_VTOL_LAND_OPTIONS
2Empty
3: Approach AltitudeApproach altitude (with the same reference as the Altitude field). NaN if unspecified.m
4: YawYaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).deg
5: LatitudeLatitude
6: LongitudeLongitude
7: Ground AltitudeAltitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value).m

MAV_CMD_NAV_GUIDED_ENABLE (92 )

[Command] hand control over to an external controller

Param (:Label)DescriptionValues
1: EnableOn / Off (> 0.5f on)min:0 max:1 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_NAV_DELAY (93 )

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

Param (:Label)DescriptionValuesUnits
1: DelayDelay (-1 to enable time-of-day fields)min: -1 increment:1s
2: Hourhour (24h format, UTC, -1 to ignore)min: -1 max:23 increment:1
3: Minuteminute (24h format, UTC, -1 to ignore)min: -1 max:59 increment:1
4: Secondsecond (24h format, UTC, -1 to ignore)min: -1 max:59 increment:1
5Empty
6Empty
7Empty

MAV_CMD_NAV_PAYLOAD_PLACE (94 )

[Command] Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Max DescentMaximum distance to descend.min:0m
2Empty
3Empty
4Empty
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_LAST (95 )

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

Param (:Label)Description
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_DELAY (112 )

[Command] Delay mission state machine.

Param (:Label)DescriptionValuesUnits
1: DelayDelaymin:0s
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_CHANGE_ALT (113 )

[Command] Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: RateDescent / Ascend rate.m/s
2Empty
3Empty
4Empty
5Empty
6Empty
7: AltitudeTarget Altitudem

MAV_CMD_CONDITION_DISTANCE (114 )

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

Param (:Label)DescriptionValuesUnits
1: DistanceDistance.min:0m
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_YAW (115 )

[Command] Reach a certain target angle.

Param (:Label)DescriptionValuesUnits
1: Angletarget angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.min:0 max:360deg
2: Angular Speedangular speedmin:0deg/s
3: Directiondirection: -1: counter clockwise, 0: shortest direction, 1: clockwisemin: -1 max:1 increment:1
4: Relative0: absolute angle, 1: relative offsetmin:0 max:1 increment:1
5Empty
6Empty
7Empty

MAV_CMD_CONDITION_LAST (159 )

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

Param (:Label)Description
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_MODE (176 )

[Command] Set system mode.

Param (:Label)DescriptionValues
1: ModeModeMAV_MODE
2: Custom ModeCustom mode - this is system specific, please refer to the individual autopilot specifications for details.
3: Custom SubmodeCustom sub mode - this is system specific, please refer to the individual autopilot specifications for details.
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_JUMP (177 )

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

Param (:Label)DescriptionValues
1: NumberSequence numbermin:0 increment:1
2: RepeatRepeat countmin:0 increment:1
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_CHANGE_SPEED (178 )

[Command] Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change

Param (:Label)DescriptionValuesUnits
1: Speed TypeSpeed type of value set in param2 (such as airspeed, ground speed, and so on)SPEED_TYPE
2: SpeedSpeed (-1 indicates no change, -2 indicates return to default vehicle speed)min: -2m/s
3: ThrottleThrottle (-1 indicates no change, -2 indicates return to default vehicle throttle value)min: -2%
4Reserved (set to 0)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_DO_SET_HOME (179 )

[Command] Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Use CurrentUse current (1=use current location, 0=use specified location)min:0 max:1 increment:1
2: RollRoll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll.min: -180 max:180deg
3: PitchPitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch.min: -90 max:90deg
4: YawYaw angle. NaN to use default heading. Range: -180..180 degrees.min: -180 max:180deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_DO_SET_PARAMETER (180 )

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

Param (:Label)DescriptionValues
1: NumberParameter numbermin:0 increment:1
2: ValueParameter value
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_RELAY (181 )

[Command] Set a relay to a condition.

Param (:Label)DescriptionValues
1: InstanceRelay instance number.min:0 increment:1
2: SettingSetting. (1=on, 0=off, others possible depending on system hardware)min:0 increment:1
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPEAT_RELAY (182 )

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

Param (:Label)DescriptionValuesUnits
1: InstanceRelay instance number.min:0 increment:1
2: CountCycle count.min:1 increment:1
3: TimeCycle time.min:0s
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_SERVO (183 )

[Command] Set a servo to a desired PWM value.

Param (:Label)DescriptionValuesUnits
1: InstanceServo instance number.min:0 increment:1
2: PWMPulse Width Modulation.min:0 increment:1us
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPEAT_SERVO (184 )

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

Param (:Label)DescriptionValuesUnits
1: InstanceServo instance number.min:0 increment:1
2: PWMPulse Width Modulation.min:0 increment:1us
3: CountCycle count.min:1 increment:1
4: TimeCycle time.min:0s
5Empty
6Empty
7Empty

MAV_CMD_DO_FLIGHTTERMINATION (185 )

[Command] Terminate flight immediately. Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground. The vehicle will ignore RC or other input until it has been power-cycled. Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing). On multicopters without a parachute it may trigger a crash landing. Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION. Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.

Param (:Label)DescriptionValues
1: TerminateFlight termination activated if > 0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED.min:0 max:1 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_CHANGE_ALTITUDE (186 )

[Command] Change altitude set point.

Param (:Label)DescriptionValuesUnits
1: AltitudeAltitude.m
2: FrameFrame of new altitude.MAV_FRAME
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ACTUATOR (187 )

[Command] Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter).

Param (:Label)DescriptionValues
1: Actuator 1Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
2: Actuator 2Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
3: Actuator 3Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
4: Actuator 4Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
5: Actuator 5Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
6: Actuator 6Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.min: -1 max:1
7: IndexIndex of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)min:0 increment:1

MAV_CMD_DO_LAND_START (189 )

[Command] 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/Altitude 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1Empty
2Empty
3Empty
4Empty
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_DO_RALLY_LAND (190 )

[Command] Mission command to perform a landing from a rally point.

Param (:Label)DescriptionUnits
1: AltitudeBreak altitudem
2: SpeedLanding speedm/s
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_GO_AROUND (191 )

[Command] Mission command to safely abort an autonomous landing.

Param (:Label)DescriptionUnits
1: AltitudeAltitudem
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_REPOSITION (192 )

[Command] Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead).

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: SpeedGround speed, less than 0 (-1) for defaultmin: -1m/s
2: BitmaskBitmask of option flags.MAV_DO_REPOSITION_FLAGS
3: RadiusLoiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored.m
4: YawYaw heading. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)deg
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_DO_PAUSE_CONTINUE (193 )

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

Param (:Label)DescriptionValues
1: Continue0: 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.min:0 max:1 increment:1
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_DO_SET_REVERSE (194 )

[Command] Set moving direction to forward or reverse.

Param (:Label)DescriptionValues
1: ReverseDirection (0=Forward, 1=Reverse)min:0 max:1 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ROI_LOCATION (195 )

[Command] Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
2Empty
3Empty
4Empty
5: LatitudeLatitude of ROI locationdegE7
6: LongitudeLongitude of ROI locationdegE7
7: AltitudeAltitude of ROI locationm

MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET (196 )

[Command] Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.

Param (:Label)DescriptionUnits
1: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
2Empty
3Empty
4Empty
5: Pitch OffsetPitch offset from next waypoint, positive pitching updeg
6: Roll OffsetRoll offset from next waypoint, positive rolling to the rightdeg
7: Yaw OffsetYaw offset from next waypoint, positive yawing to the rightdeg

MAV_CMD_DO_SET_ROI_NONE (197 )

[Command] Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position.

Param (:Label)Description
1: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ROI_SYSID (198 )

[Command] Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message.

Param (:Label)DescriptionValues
1: System IDSystem IDmin:1 max:255 increment:1
2: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).

MAV_CMD_DO_CONTROL_VIDEO (200 )

[Command] Control onboard camera system.

Param (:Label)DescriptionValuesUnits
1: IDCamera ID (-1 for all)min: -1 increment:1
2: TransmissionTransmission: 0: disabled, 1: enabled compressed, 2: enabled rawmin:0 max:2 increment:1
3: IntervalTransmission mode: 0: video stream, >0: single images every n secondsmin:0s
4: RecordingRecording: 0: disabled, 1: enabled compressed, 2: enabled rawmin:0 max:2 increment:1
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_ROI (201 )

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

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValues
1: ROI ModeRegion of interest mode.MAV_ROI
2: WP IndexWaypoint index/ target ID (depends on param 1).min:0 increment:1
3: ROI IndexRegion of interest index. (allows a vehicle to manage multiple ROI's)min:0 increment:1
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 )

[Command] Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).

Param (:Label)DescriptionValuesUnits
1: ModeModes: P, TV, AV, M, Etc.min:0 increment:1
2: Shutter SpeedShutter speed: Divisor number for one second.min:0 increment:1
3: ApertureAperture: F stop number.min:0
4: ISOISO number e.g. 80, 100, 200, Etc.min:0 increment:1
5: ExposureExposure type enumerator.
6: Command IdentityCommand Identity.
7: Engine Cut-offMain engine cut-off time before camera trigger. (0 means no cut-off)min:0 increment:1ds

MAV_CMD_DO_DIGICAM_CONTROL (203 )

[Command] Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ).

Param (:Label)Description
1: Session ControlSession control e.g. show/hide lens
2: Zoom AbsoluteZoom's absolute position
3: Zoom RelativeZooming step value to offset zoom from the current position
4: FocusFocus Locking, Unlocking or Re-locking
5: Shoot CommandShooting Command
6: Command IdentityCommand Identity
7: Shot IDTest shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.

MAV_CMD_DO_MOUNT_CONFIGURE (204 )

DEPRECATED: Replaced by MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE (2020-01). This message has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE. The message can still be used to communicate with legacy gimbals implementing it.

[Command] Mission command to configure a camera or antenna mount

Param (:Label)DescriptionValues
1: ModeMount operation modeMAV_MOUNT_MODE
2: Stabilize Rollstabilize roll? (1 = yes, 0 = no)min:0 max:1 increment:1
3: Stabilize Pitchstabilize pitch? (1 = yes, 0 = no)min:0 max:1 increment:1
4: Stabilize Yawstabilize yaw? (1 = yes, 0 = no)min:0 max:1 increment:1
5: Roll Input Moderoll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
6: Pitch Input Modepitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)
7: Yaw Input Modeyaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)

MAV_CMD_DO_MOUNT_CONTROL (205 )

DEPRECATED: Replaced by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW (2020-01). This message is ambiguous and inconsistent. It has been superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW and MAV_CMD_DO_SET_ROI_*. The message can still be used to communicate with legacy gimbals implementing it.

[Command] Mission command to control a camera or antenna mount

Param (:Label)DescriptionValuesUnits
1: Pitchpitch depending on mount mode (degrees or degrees/second depending on pitch input).
2: Rollroll depending on mount mode (degrees or degrees/second depending on roll input).
3: Yawyaw depending on mount mode (degrees or degrees/second depending on yaw input).
4: Altitudealtitude depending on mount mode.m
5: Latitudelatitude, set if appropriate mount mode.
6: Longitudelongitude, set if appropriate mount mode.
7: ModeMount mode.MAV_MOUNT_MODE

MAV_CMD_DO_SET_CAM_TRIGG_DIST (206 )

[Command] 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.

Param (:Label)DescriptionValuesUnits
1: DistanceCamera trigger distance. 0 to stop triggering.min:0m
2: ShutterCamera shutter integration time. -1 or 0 to ignoremin: -1 increment:1ms
3: TriggerTrigger camera once immediately. (0 = no trigger, 1 = trigger)min:0 max:1 increment:1
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_FENCE_ENABLE (207 )

[Command] Mission command to enable the geofence

Param (:Label)DescriptionValues
1: Enableenable? (0=disable, 1=enable, 2=disable_floor_only)min:0 max:2 increment:1
2: TypesFence types to enable or disable as a bitmask. A value of 0 indicates that all fences should be enabled or disabled. This parameter is ignored if param 1 has the value 2FENCE_TYPE
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_PARACHUTE (208 )

[Command] Mission item/command to release a parachute or enable/disable auto release.

Param (:Label)DescriptionValues
1: ActionActionPARACHUTE_ACTION
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_MOTOR_TEST (209 )

[Command] Command to perform motor test.

Param (:Label)DescriptionValuesUnits
1: InstanceMotor instance number (from 1 to max number of motors on the vehicle).min:1 increment:1
2: Throttle TypeThrottle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.)MOTOR_TEST_THROTTLE_TYPE
3: ThrottleThrottle value.
4: TimeoutTimeout between tests that are run in sequence.min:0s
5: Motor CountMotor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests.min:0 increment:1
6: Test OrderMotor test order.MOTOR_TEST_ORDER
7Empty

MAV_CMD_DO_INVERTED_FLIGHT (210 )

[Command] Change to/from inverted flight.

Param (:Label)DescriptionValues
1: InvertedInverted flight. (0=normal, 1=inverted)min:0 max:1 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_GRIPPER (211 )

[Command] Mission command to operate a gripper.

Param (:Label)DescriptionValues
1: InstanceGripper instance number.min:1 increment:1
2: ActionGripper action to perform.GRIPPER_ACTIONS
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_AUTOTUNE_ENABLE (212 )

[Command] Enable/disable autotune.

Param (:Label)DescriptionValues
1: EnableEnable (1: enable, 0:disable).min:0 max:1 increment:1
2: AxisSpecify which axis are autotuned. 0 indicates autopilot default settings.AUTOTUNE_AXIS
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_NAV_SET_YAW_SPEED (213 )

[Command] Sets a desired vehicle turn angle and speed change.

Param (:Label)DescriptionValuesUnits
1: YawYaw angle to adjust steering by.deg
2: SpeedSpeed.m/s
3: AngleFinal angle. (0=absolute, 1=relative)min:0 max:1 increment:1
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL (214 )

[Command] 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.

Param (:Label)DescriptionValuesUnits
1: Trigger CycleCamera trigger cycle time. -1 or 0 to ignore.min: -1 increment:1ms
2: Shutter IntegrationCamera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.min: -1 increment:1ms
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_MOUNT_CONTROL_QUAT (220 )

DEPRECATED: Replaced by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW (2020-01).

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

Param (:Label)Description
1: Q1quaternion param q1, w (1 in null-rotation)
2: Q2quaternion param q2, x (0 in null-rotation)
3: Q3quaternion param q3, y (0 in null-rotation)
4: Q4quaternion param q4, z (0 in null-rotation)
5Empty
6Empty
7Empty

MAV_CMD_DO_GUIDED_MASTER (221 )

[Command] set id of master controller

Param (:Label)DescriptionValues
1: System IDSystem IDmin:0 max:255 increment:1
2: Component IDComponent IDmin:0 max:255 increment:1
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_GUIDED_LIMITS (222 )

[Command] Set limits for external control

Param (:Label)DescriptionValuesUnits
1: TimeoutTimeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.min:0s
2: Min AltitudeAltitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.m
3: Max AltitudeAltitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.m
4: Horiz. Move LimitHorizontal move limit - 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.min:0m
5Empty
6Empty
7Empty

MAV_CMD_DO_ENGINE_CONTROL (223 )

[Command] 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

Param (:Label)DescriptionValuesUnits
1: Start Engine0: Stop engine, 1:Start Enginemin:0 max:1 increment:1
2: Cold Start0: Warm start, 1:Cold start. Controls use of choke where applicablemin:0 max:1 increment:1
3: Height DelayHeight delay. 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.min:0m
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_SET_MISSION_CURRENT (224 )

[Command] Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be "reset" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item).

Param (:Label)DescriptionValues
1: NumberMission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item).min: -1 increment:1
2: Reset MissionResets mission. 1: true, 0: false. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused".min:0 max:1 increment:1
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_DO_LAST (240 )

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

Param (:Label)Description
1Empty
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_PREFLIGHT_CALIBRATION (241 )

[Command] 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.

Param (:Label)DescriptionValues
1: Gyro Temperature1: gyro calibration, 3: gyro temperature calibrationmin:0 max:3 increment:1
2: Magnetometer1: magnetometer calibrationmin:0 max:1 increment:1
3: Ground Pressure1: ground pressure calibrationmin:0 max:1 increment:1
4: Remote Control1: radio RC calibration, 2: RC trim calibrationmin:0 max:1 increment:1
5: Accelerometer1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibrationmin:0 max:4 increment:1
6: Compmot or Airspeed1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibrationmin:0 max:2 increment:1
7: ESC or Baro1: ESC calibration, 3: barometer temperature calibrationmin:0 max:3 increment:1

MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (242 )

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

Param (:Label)DescriptionValues
1: Sensor TypeSensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometermin:0 max:6 increment:1
2: X OffsetX axis offset (or generic dimension 1), in the sensor's raw units
3: Y OffsetY axis offset (or generic dimension 2), in the sensor's raw units
4: Z OffsetZ axis offset (or generic dimension 3), in the sensor's raw units
5: 4th DimensionGeneric dimension 4, in the sensor's raw units
6: 5th DimensionGeneric dimension 5, in the sensor's raw units
7: 6th DimensionGeneric dimension 6, in the sensor's raw units

MAV_CMD_PREFLIGHT_UAVCAN (243 )

[Command] Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named).

Param (:Label)Description
1: Actuator ID1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_PREFLIGHT_STORAGE (245 )

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

Param (:Label)DescriptionValuesUnits
1: Parameter StorageAction to perform on the persistent parameter storagePREFLIGHT_STORAGE_PARAMETER_ACTION
2: Mission StorageAction to perform on the persistent mission storagePREFLIGHT_STORAGE_MISSION_ACTION
3: Logging RateOnboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging)min: -1 increment:1Hz
4Reserved
5Empty
6Empty
7Empty

MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246 )

[Command] Request the reboot or shutdown of system components.

Param (:Label)DescriptionValues
1: Autopilot0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot, 3: Reboot autopilot and keep it in the bootloader until upgraded.min:0 max:3 increment:1
2: Companion0: 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.min:0 max:3 increment:1
3: Component action0: Do nothing for component, 1: Reboot component, 2: Shutdown component, 3: Reboot component and keep it in the bootloader until upgradedmin:0 max:3 increment:1
4: Component IDMAVLink Component ID targeted in param3 (0 for all components).min:0 max:255 increment:1
5Reserved (set to 0)
6Reserved (set to 0)
7WIP: ID (e.g. camera ID -1 for all IDs)

MAV_CMD_OVERRIDE_GOTO (252 )

[Command] Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: ContinueMAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.MAV_GOTO
2: PositionMAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.MAV_GOTO
3: FrameCoordinate frame of hold point.MAV_FRAME
4: YawDesired yaw angle.deg
5: Latitude/XLatitude/X position.
6: Longitude/YLongitude/Y position.
7: Altitude/ZAltitude/Z position.

MAV_CMD_OBLIQUE_SURVEY (260 )

[Command] Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera.

Param (:Label)DescriptionValuesUnits
1: DistanceCamera trigger distance. 0 to stop triggering.min:0m
2: ShutterCamera shutter integration time. 0 to ignoremin:0 increment:1ms
3: Min IntervalThe minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.min:0 max:10000 increment:1ms
4: PositionsTotal number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).min:2 increment:1
5: Roll AngleAngle limits that the camera can be rolled to left and right of center.min:0deg
6: Pitch AngleFixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.min: -180 max:180deg
7Empty

MAV_CMD_MISSION_START (300 )

[Command] start running a mission

Param (:Label)DescriptionValues
1: First Itemfirst_item: the first mission item to runmin:0 increment:1
2: Last Itemlast_item: the last mission item to run (after this item is run, the mission ends)min:0 increment:1

MAV_CMD_ACTUATOR_TEST (310 )

[Command] Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots typically refuse this command while armed.

Param (:Label)DescriptionValuesUnits
1: ValueOutput value: 1 means maximum positive output, 0 to center servos or minimum motor thrust (expected to spin), -1 for maximum negative (if not supported by the motors, i.e. motor is not reversible, smaller than 0 maps to NaN). And NaN maps to disarmed (stop the motors).min: -1 max:1
2: TimeoutTimeout after which the test command expires and the output is restored to the previous value. A timeout has to be set for safety reasons. A timeout of 0 means to restore the previous value immediately.min:0 max:3s
3Reserved (set to 0)
4Reserved (set to 0)
5: Output FunctionActuator Output functionACTUATOR_OUTPUT_FUNCTION
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_CONFIGURE_ACTUATOR (311 )

[Command] Actuator configuration command.

Param (:Label)DescriptionValues
1: ConfigurationActuator configuration actionACTUATOR_CONFIGURATION
2Reserved (set to 0)
3Reserved (set to 0)
4Reserved (set to 0)
5: Output FunctionActuator Output functionACTUATOR_OUTPUT_FUNCTION
6Reserved (set to 0)
7Reserved (set to 0)

MAV_CMD_COMPONENT_ARM_DISARM (400 )

[Command] Arms / Disarms a component

Param (:Label)DescriptionValues
1: Arm0: disarm, 1: armmin:0 max:1 increment:1
2: Force0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)min:0 max:21196 increment:21196

MAV_CMD_RUN_PREARM_CHECKS (401 )

[Command] Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed.

Param (:Label)Description

MAV_CMD_ILLUMINATOR_ON_OFF (405 )

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

[Command] Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light).

Param (:Label)DescriptionValues
1: Enable0: Illuminators OFF, 1: Illuminators ONmin:0 max:1 increment:1

MAV_CMD_GET_HOME_POSITION (410 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2022-04).

[Command] Request the home position from the vehicle. The vehicle will ACK the command and then emit the HOME_POSITION message.

Param (:Label)Description
1Reserved
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_INJECT_FAILURE (420 )

[Command] Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting.

Param (:Label)DescriptionValues
1: Failure unitThe unit which is affected by the failure.FAILURE_UNIT
2: Failure typeThe type how the failure manifests itself.FAILURE_TYPE
3: InstanceInstance affected by failure (0 to signal all).

MAV_CMD_START_RX_PAIR (500 )

[Command] Starts receiver pairing.

Param (:Label)DescriptionValues
1: Spektrum0:Spektrum.
2: RC TypeRC type.RC_TYPE

MAV_CMD_GET_MESSAGE_INTERVAL (510 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2022-04).

[Command] Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message.

Param (:Label)DescriptionValues
1: Message IDThe MAVLink message IDmin:0 max:16777215 increment:1

MAV_CMD_SET_MESSAGE_INTERVAL (511 )

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

Param (:Label)DescriptionValuesUnits
1: Message IDThe MAVLink message IDmin:0 max:16777215 increment:1
2: IntervalThe interval between two messages. -1: disable. 0: request default rate (which may be zero).min: -1 increment:1us
7: Response TargetTarget address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requestor, 2: broadcast.min:0 max:2 increment:1

MAV_CMD_REQUEST_MESSAGE (512 )

[Command] Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL).

Param (:Label)DescriptionValues
1: Message IDThe MAVLink message ID of the requested message.min:0 max:16777215 increment:1
2: Req Param 1Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).
3: Req Param 2The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).
4: Req Param 3The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).
5: Req Param 4The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).
6: Req Param 5The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).
7: Response TargetTarget address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requestor, 2: broadcast.min:0 max:2 increment:1

MAV_CMD_REQUEST_PROTOCOL_VERSION (519 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message

Param (:Label)DescriptionValues
1: Protocol1: Request supported protocol versions by all nodes on the networkmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES (520 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message

Param (:Label)DescriptionValues
1: Version1: Request autopilot versionmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_INFORMATION (521 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request camera information (CAMERA_INFORMATION).

Param (:Label)DescriptionValues
1: Capabilities0: No action 1: Request camera capabilitiesmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_SETTINGS (522 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request camera settings (CAMERA_SETTINGS).

Param (:Label)DescriptionValues
1: Settings0: No Action 1: Request camera settingsmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_REQUEST_STORAGE_INFORMATION (525 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

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

Param (:Label)DescriptionValues
1: Storage IDStorage ID (0 for all, 1 for first, 2 for second, etc.)min:0 increment:1
2: Information0: No Action 1: Request storage informationmin:0 max:1 increment:1
3Reserved (all remaining params)

MAV_CMD_STORAGE_FORMAT (526 )

[Command] 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.

Param (:Label)DescriptionValues
1: Storage IDStorage ID (1 for first, 2 for second, etc.)min:0 increment:1
2: FormatFormat storage (and reset image log). 0: No action 1: Format storagemin:0 max:1 increment:1
3: Reset Image LogReset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. 0: No action 1: Reset Image Logmin:0 max:1 increment:1
4Reserved (all remaining params)

MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (527 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request camera capture status (CAMERA_CAPTURE_STATUS)

Param (:Label)DescriptionValues
1: Capture Status0: No Action 1: Request camera capture statusmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_REQUEST_FLIGHT_INFORMATION (528 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request flight information (FLIGHT_INFORMATION)

Param (:Label)DescriptionValues
1: Flight Information1: Request flight informationmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_RESET_CAMERA_SETTINGS (529 )

[Command] Reset all camera settings to Factory Default

Param (:Label)DescriptionValues
1: Reset0: No Action 1: Reset all settingsmin:0 max:1 increment:1
2Reserved (all remaining params)

MAV_CMD_SET_CAMERA_MODE (530 )

[Command] Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming.

Param (:Label)DescriptionValues
1Reserved (Set to 0)
2: Camera ModeCamera modeCAMERA_MODE
3Reserved (set to NaN)
4Reserved (set to NaN)
7Reserved (set to NaN)

MAV_CMD_SET_CAMERA_ZOOM (531 )

[Command] Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success).

Param (:Label)DescriptionValues
1: Zoom TypeZoom typeCAMERA_ZOOM_TYPE
2: Zoom ValueZoom value. The range of valid values depend on the zoom type.
3Reserved (set to NaN)
4Reserved (set to NaN)
7Reserved (set to NaN)

MAV_CMD_SET_CAMERA_FOCUS (532 )

[Command] Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success).

Param (:Label)DescriptionValues
1: Focus TypeFocus typeSET_FOCUS_TYPE
2: Focus ValueFocus value
3Reserved (set to NaN)
4Reserved (set to NaN)
7Reserved (set to NaN)

MAV_CMD_SET_STORAGE_USAGE (533 )

[Command] Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED.

Param (:Label)DescriptionValues
1: Storage IDStorage ID (1 for first, 2 for second, etc.)min:0 increment:1
2: UsageUsage flagsSTORAGE_USAGE_FLAG

MAV_CMD_SET_CAMERA_SOURCE (534 )

[Command] Set camera source. Changes the camera's active sources on cameras with multiple image sensors.

Param (:Label)DescriptionValues
1: device idComponent Id of camera to address or 1-6 for non-MAVLink cameras, 0 for all cameras.
2: primary sourcePrimary SourceCAMERA_SOURCE
3: secondary sourceSecondary Source. If non-zero the second source will be displayed as picture-in-picture.CAMERA_SOURCE

MAV_CMD_JUMP_TAG (600 )

[Command] Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG.

Param (:Label)DescriptionValues
1: TagTag.min:0 increment:1

MAV_CMD_DO_JUMP_TAG (601 )

[Command] Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number.

Param (:Label)DescriptionValues
1: TagTarget tag to jump to.min:0 increment:1
2: RepeatRepeat count.min:0 increment:1

MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW (1000 )

[Command] Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate.

Param (:Label)DescriptionValuesUnits
1: Pitch anglePitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).min: -180 max:180deg
2: Yaw angleYaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).min: -180 max:180deg
3: Pitch ratePitch rate (positive to pitch up).deg/s
4: Yaw rateYaw rate (positive to yaw to the right).deg/s
5: Gimbal manager flagsGimbal manager flags to use.GIMBAL_MANAGER_FLAGS
7: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).

MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE (1001 )

[Command] Gimbal configuration to set which sysid/compid is in primary and secondary control.

Param (:Label)Description
1: sysid primary controlSysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).
2: compid primary controlCompid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).
3: sysid secondary controlSysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).
4: compid secondary controlCompid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).
7: Gimbal device IDComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).

MAV_CMD_IMAGE_START_CAPTURE (2000 )

[Command] Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.

Param (:Label)DescriptionValuesUnits
1: idTarget camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a missionmin:0 max:255 increment:1
2: IntervalDesired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).min:0s
3: Total ImagesTotal number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.min:0 increment:1
4: Sequence NumberCapture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.min:1 increment:1
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_IMAGE_STOP_CAPTURE (2001 )

[Command] Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.

Param (:Label)DescriptionValues
1: idTarget camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras that don't have a distinct component id (such as autopilot-attached cameras). 0: all cameras. This is used to specifically target autopilot-connected cameras or individual sensors in a multi-sensor MAVLink camera. It is also used to target specific cameras when the MAV_CMD is used in a missionmin:0 max:255 increment:1
2Reserved (set to NaN)
3Reserved (set to NaN)
4Reserved (set to NaN)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE (2002 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Re-request a CAMERA_IMAGE_CAPTURED message.

Param (:Label)DescriptionValues
1: NumberSequence number for missing CAMERA_IMAGE_CAPTURED messagemin:0 increment:1
2Reserved (set to NaN)
3Reserved (set to NaN)
4Reserved (set to NaN)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_DO_TRIGGER_CONTROL (2003 )

[Command] Enable or disable on-board camera triggering system.

Param (:Label)DescriptionValues
1: EnableTrigger enable/disable (0 for disable, 1 for start), -1 to ignoremin: -1 max:1 increment:1
2: Reset1 to reset the trigger sequence, -1 or 0 to ignoremin: -1 max:1 increment:1
3: Pause1 to pause triggering, but without switching the camera off or retracting it. -1 to ignoremin: -1 max:1 increment:2

MAV_CMD_CAMERA_TRACK_POINT (2004 )

[Command] If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking.

Param (:Label)DescriptionValues
1: Point xPoint to track x value (normalized 0..1, 0 is left, 1 is right).min:0 max:1
2: Point yPoint to track y value (normalized 0..1, 0 is top, 1 is bottom).min:0 max:1
3: RadiusPoint radius (normalized 0..1, 0 is image left, 1 is image right).min:0 max:1

MAV_CMD_CAMERA_TRACK_RECTANGLE (2005 )

[Command] If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking.

Param (:Label)DescriptionValues
1: Top left corner xTop left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).min:0 max:1
2: Top left corner yTop left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).min:0 max:1
3: Bottom right corner xBottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).min:0 max:1
4: Bottom right corner yBottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).min:0 max:1

MAV_CMD_CAMERA_STOP_TRACKING (2010 )

[Command] Stops ongoing tracking.

Param (:Label)Description

MAV_CMD_VIDEO_START_CAPTURE (2500 )

[Command] Starts video capture (recording).

Param (:Label)DescriptionValuesUnits
1: Stream IDVideo Stream ID (0 for all streams)min:0 increment:1
2: Status FrequencyFrequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency)min:0Hz
3Reserved (set to NaN)
4Reserved (set to NaN)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_VIDEO_STOP_CAPTURE (2501 )

[Command] Stop the current video capture (recording).

Param (:Label)DescriptionValues
1: Stream IDVideo Stream ID (0 for all streams)min:0 increment:1
2Reserved (set to NaN)
3Reserved (set to NaN)
4Reserved (set to NaN)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_VIDEO_START_STREAMING (2502 )

[Command] Start video streaming

Param (:Label)DescriptionValues
1: Stream IDVideo Stream ID (0 for all streams, 1 for first, 2 for second, etc.)min:0 increment:1

MAV_CMD_VIDEO_STOP_STREAMING (2503 )

[Command] Stop the given video stream

Param (:Label)DescriptionValues
1: Stream IDVideo Stream ID (0 for all streams, 1 for first, 2 for second, etc.)min:0 increment:1

MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (2504 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request video stream information (VIDEO_STREAM_INFORMATION)

Param (:Label)DescriptionValues
1: Stream IDVideo Stream ID (0 for all streams, 1 for first, 2 for second, etc.)min:0 increment:1

MAV_CMD_REQUEST_VIDEO_STREAM_STATUS (2505 )

DEPRECATED: Replaced by MAV_CMD_REQUEST_MESSAGE (2019-08).

[Command] Request video stream status (VIDEO_STREAM_STATUS)

Param (:Label)DescriptionValues
1: Stream IDVideo Stream ID (0 for all streams, 1 for first, 2 for second, etc.)min:0 increment:1

MAV_CMD_LOGGING_START (2510 )

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

Param (:Label)DescriptionValues
1: FormatFormat: 0: ULogmin:0 increment:1
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 )

[Command] Request to stop streaming log data over MAVLink

Param (:Label)Description
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 )

[Command]

Param (:Label)DescriptionValues
1: Landing Gear IDLanding gear ID (default: 0, -1 for all)min: -1 increment:1
2: Landing Gear PositionLanding gear position (Down: 0, Up: 1, NaN for no change)
3Reserved (set to NaN)
4Reserved (set to NaN)
5Reserved (set to 0)
6Reserved (set to 0)
7Reserved (set to NaN)

MAV_CMD_CONTROL_HIGH_LATENCY (2600 )

[Command] Request to start/stop transmitting over the high latency telemetry

Param (:Label)DescriptionValues
1: EnableControl transmission over high latency telemetry (0: stop, 1: start)min:0 max:1 increment:1
2Empty
3Empty
4Empty
5Empty
6Empty
7Empty

MAV_CMD_PANORAMA_CREATE (2800 )

[Command] Create a panorama at the current position

Param (:Label)DescriptionUnits
1: Horizontal AngleViewing angle horizontal of the panorama (+- 0.5 the total angle)deg
2: Vertical AngleViewing angle vertical of panorama.deg
3: Horizontal SpeedSpeed of the horizontal rotation.deg/s
4: Vertical SpeedSpeed of the vertical rotation.deg/s

MAV_CMD_DO_VTOL_TRANSITION (3000 )

[Command] Request VTOL transition

Param (:Label)DescriptionValues
1: StateThe target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.MAV_VTOL_STATE
2: ImmediateForce immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.

MAV_CMD_ARM_AUTHORIZATION_REQUEST (3001 )

[Command] 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 COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON.

Param (:Label)DescriptionValues
1: System IDVehicle system id, this way ground station can request arm authorization on behalf of any vehiclemin:0 max:255 increment:1

MAV_CMD_SET_GUIDED_SUBMODE_STANDARD (4000 )

[Command] 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.

Param (:Label)Description

MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE (4001 )

[Command] 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: RadiusRadius of desired circle in CIRCLE_MODEm
2User defined
3User defined
4User defined
5: LatitudeTarget latitude of center of circle in CIRCLE_MODEdegE7
6: LongitudeTarget longitude of center of circle in CIRCLE_MODEdegE7

MAV_CMD_CONDITION_GATE (4501 )

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

[Command] Delay mission state machine until gate has been reached.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: GeometryGeometry: 0: orthogonal to path between previous and next waypoint.min:0 increment:1
2: UseAltitudeAltitude: 0: ignore altitudemin:0 max:1 increment:1
3Empty
4Empty
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_FENCE_RETURN_POINT (5000 )

[Command] Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1Reserved
2Reserved
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION (5001 )

[Command] 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValues
1: Vertex CountPolygon vertex countmin:3 increment:1
2: Inclusion GroupVehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygonmin:0 increment:1
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7Reserved

MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION (5002 )

[Command] 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.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValues
1: Vertex CountPolygon vertex countmin:3 increment:1
2Reserved
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7Reserved

MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION (5003 )

[Command] Circular fence area. The vehicle must stay inside this area.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: RadiusRadius.m
2: Inclusion GroupVehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one groupmin:0 increment:1
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7Reserved

MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION (5004 )

[Command] Circular fence area. The vehicle must stay outside this area.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: RadiusRadius.m
2Reserved
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7Reserved

MAV_CMD_NAV_RALLY_POINT (5100 )

[Command] Rally point. You can have multiple rally points defined.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1Reserved
2Reserved
3Reserved
4Reserved
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitudem

MAV_CMD_UAVCAN_GET_NODE_INFO (5200 )

[Command] 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.

Param (:Label)Description
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_DO_SET_SAFETY_SWITCH_STATE (5300 )

[Command] Change state of safety switch.

Param (:Label)DescriptionValues
1: Desired StateNew safety switch state.SAFETY_SWITCH_STATE
2Empty.
3Empty.
4Empty
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_ADSB_OUT_IDENT (10001 )

[Command] Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec.

Param (:Label)Description
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 )

DEPRECATED: Replaced by (2021-06).

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionValuesUnits
1: Operation ModeOperation 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.min:0 max:2 increment:1
2: Approach VectorDesired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.min: -1 max:360deg
3: Ground SpeedDesired 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.min: -1
4: Altitude ClearanceMinimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.min: -1m
5: LatitudeLatitude.degE7
6: LongitudeLongitude.degE7
7: AltitudeAltitude (MSL)m

MAV_CMD_PAYLOAD_CONTROL_DEPLOY (30002 )

DEPRECATED: Replaced by (2021-06).

[Command] Control the payload deployment.

Param (:Label)DescriptionValues
1: Operation ModeOperation 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.min:0 max:101 increment:1
2Reserved
3Reserved
4Reserved
5Reserved
6Reserved
7Reserved

MAV_CMD_FIXED_MAG_CAL_YAW (42006 )

[Command] Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location.

Param (:Label)DescriptionUnits
1: YawYaw of vehicle in earth frame.deg
2: CompassMaskCompassMask, 0 for all.
3: LatitudeLatitude.deg
4: LongitudeLongitude.deg
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_WINCH (42600 )

[Command] Command to operate winch.

Param (:Label)DescriptionValuesUnits
1: InstanceWinch instance number.min:1 increment:1
2: ActionAction to perform.WINCH_ACTIONS
3: LengthLength of line to release (negative to wind).m
4: RateRelease rate (negative to wind).m/s
5Empty.
6Empty.
7Empty.

MAV_CMD_EXTERNAL_POSITION_ESTIMATE (43003 )

[Command] Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1: transmission_timeTimestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy.s
2: processing_timeThe time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known.s
3: accuracyestimated one standard deviation accuracy of the measurement. Set to NaN if not known.
4Empty
5: LatitudeLatitude
6: LongitudeLongitude
7: AltitudeAltitude, not used. Should be sent as NaN. May be supported in a future version of this message.m

MAV_CMD_WAYPOINT_USER_1 (31000 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_WAYPOINT_USER_2 (31001 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_WAYPOINT_USER_3 (31002 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_WAYPOINT_USER_4 (31003 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_WAYPOINT_USER_5 (31004 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_SPATIAL_USER_1 (31005 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_SPATIAL_USER_2 (31006 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_SPATIAL_USER_3 (31007 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_SPATIAL_USER_4 (31008 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_SPATIAL_USER_5 (31009 )

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

Send this command in a COMMAND_INT (if supported by your flight stack), as it specifies positional information. If sent in a COMMAND_LONG, no frame of reference can be set, and lat/lon values in param 5/6 are less precise.

Param (:Label)DescriptionUnits
1User defined
2User defined
3User defined
4User defined
5: LatitudeLatitude unscaled
6: LongitudeLongitude unscaled
7: AltitudeAltitude (MSL)m

MAV_CMD_USER_1 (31010 )

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

Param (:Label)Description
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_2 (31011 )

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

Param (:Label)Description
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_3 (31012 )

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

Param (:Label)Description
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_4 (31013 )

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

Param (:Label)Description
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_USER_5 (31014 )

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

Param (:Label)Description
1User defined
2User defined
3User defined
4User defined
5User defined
6User defined
7User defined

MAV_CMD_CAN_FORWARD (32000 )

[Command] Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages

Param (:Label)Description
1: busBus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus).
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAVLink Messages

SYS_STATUS ( #1 )

[Message] 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 have an error (or are operational). Value of 0: error. Value of 1: healthy.
loaduint16_td%Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000
voltage_batteryuint16_tmVBattery voltage, UINT16_MAX: Voltage not sent by autopilot
current_batteryint16_tcABattery current, -1: Current not sent by autopilot
battery_remainingint8_t%Battery energy remaining, -1: Battery remaining energy not sent by autopilot
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
onboard_control_sensors_present_extended **uint32_tMAV_SYS_STATUS_SENSOR_EXTENDEDBitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present.
onboard_control_sensors_enabled_extended **uint32_tMAV_SYS_STATUS_SENSOR_EXTENDEDBitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled.
onboard_control_sensors_health_extended **uint32_tMAV_SYS_STATUS_SENSOR_EXTENDEDBitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy.

SYSTEM_TIME ( #2 )

[Message] 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 )

DEPRECATED: Replaced by SYSTEM_TIME (2011-08). to be removed / merged with SYSTEM_TIME

[Message] A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at https://mavlink.io/en/services/ping.html

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

[Message] 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 )

[Message] 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 )

[Message] 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

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

[Message] Status generated in each node in the communication chain and injected into MAVLink stream.

Field NameTypeUnitsDescription
timestampuint64_tmsTimestamp (time since system boot).
tx_bufuint8_t%Remaining free transmit buffer space
rx_bufuint8_t%Remaining free receive buffer space
tx_rateuint32_tbytes/sTransmit rate
rx_rateuint32_tbytes/sReceive rate
rx_parse_erruint16_tbytesNumber of bytes that could not be parsed correctly.
tx_overflowsuint16_tbytesTransmit buffer overflows. This number wraps around as it reaches UINT16_MAX
rx_overflowsuint16_tbytesReceive buffer overflows. This number wraps around as it reaches UINT16_MAX
messages_sentuint32_tMessages sent
messages_receiveduint32_tMessages received (estimated from counting seq)
messages_lostuint32_tMessages lost (estimated from counting seq)

SET_MODE ( #11 )

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

[Message] 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 )

[Message] Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code.

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 )

[Message] Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

PARAM_VALUE ( #22 )

[Message] Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

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 )

[Message] Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received.

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 )

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

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 of 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 * 100). If unknown, set to: UINT16_MAX
epvuint16_tGPS VDOP vertical dilution of position (unitless * 100). 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 UINT8_MAX
alt_ellipsoid **int32_tmmAltitude (above WGS84, EGM96 ellipsoid). Positive for up.
h_acc **uint32_tmmPosition uncertainty.
v_acc **uint32_tmmAltitude uncertainty.
vel_acc **uint32_tmmSpeed uncertainty.
hdg_acc **uint32_tdegE5Heading / track uncertainty
yaw **uint16_tcdegYaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.

GPS_STATUS ( #25 )

[Message] The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites.

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 )

[Message] 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_tmgaussX Magnetic field
ymagint16_tmgaussY Magnetic field
zmagint16_tmgaussZ Magnetic field
temperature **int16_tcdegCTemperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).

RAW_IMU ( #27 )

[Message] The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging.

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 of 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)
id **uint8_tId. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
temperature **int16_tcdegCTemperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).

RAW_PRESSURE ( #28 )

[Message] 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 of 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 )

[Message] 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_tcdegCAbsolute pressure temperature
temperature_press_diff **int16_tcdegCDifferential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.

ATTITUDE ( #30 )

[Message] The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic).

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 )

[Message] 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
repr_offset_q **float[4]Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.

LOCAL_POSITION_NED ( #32 )

[Message] 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 )

[Message] 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 )

[Message] The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
portuint8_tServo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
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_tReceive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.

RC_CHANNELS_RAW ( #35 )

[Message] 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). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
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_tReceive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.

SERVO_OUTPUT_RAW ( #36 )

[Message] Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.

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 of the number.
portuint8_tServo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX.
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 )

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

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
start_indexint16_tStart index
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 )

[Message] 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. Must be 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 )

DEPRECATED: Replaced by MISSION_ITEM_INT (2020-06).

[Message] Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.

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. 0: false, 1: true. Set false to pause mission after the item completes.
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 )

DEPRECATED: Replaced by MISSION_REQUEST_INT (2020-06). A system that gets this request should respond with MISSION_ITEM_INT (as though MISSION_REQUEST_INT was received).

[Message] Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. https://mavlink.io/en/services/mission.html

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

MISSION_SET_CURRENT ( #41 )

DEPRECATED: Replaced by MAV_CMD_DO_SET_MISSION_CURRENT (2022-08).

[Message] Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequint16_tSequence

MISSION_CURRENT ( #42 )

[Message] Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or SET_MISSION_CURRENT.

Field NameTypeValuesDescription
sequint16_tSequence
total **uint16_tTotal number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.
mission_state **uint8_tMISSION_STATEMission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.
mission_mode **uint8_tVehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).
mission_id **uint32_tId of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK).
fence_id **uint32_tId of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK).
rally_points_id **uint32_tId of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK).

MISSION_REQUEST_LIST ( #43 )

[Message] 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 )

[Message] 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.
opaque_id **uint32_tId of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK).

MISSION_CLEAR_ALL ( #45 )

[Message] 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 )

[Message] 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 )

[Message] 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.
opaque_id **uint32_tId of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded.

SET_GPS_GLOBAL_ORIGIN ( #48 )

[Message] Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.

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 of the number.

GPS_GLOBAL_ORIGIN ( #49 )

[Message] Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.

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 of the number.

PARAM_MAP_RC ( #50 )

[Message] 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 )

[Message] Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. https://mavlink.io/en/services/mission.html

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

SAFETY_SET_ALLOWED_AREA ( #54 )

[Message] 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 )

[Message] 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 )

[Message] 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 of 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]Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.

[Message] The state of the 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 )

[Message] 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 of 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]Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.

LOCAL_POSITION_NED_COV ( #64 )

[Message] 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 of 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]Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array.

RC_CHANNELS ( #65 )

[Message] 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_tReceive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.

REQUEST_DATA_STREAM ( #66 )

DEPRECATED: Replaced by MAV_CMD_SET_MESSAGE_INTERVAL (2015-08).

[Message] 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).

[Message] 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 )

[Message] This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask

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' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
buttons2 **uint16_tA bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
enabled_extensions **uint8_tSet bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
s **int16_tPitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.
t **int16_tRoll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.
aux1 **int16_tAux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset.
aux2 **int16_tAux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset.
aux3 **int16_tAux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset.
aux4 **int16_tAux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset.
aux5 **int16_tAux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset.
aux6 **int16_tAux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset.

RC_CHANNELS_OVERRIDE ( #70 )

[Message] The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels

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. A value of 0 means to release this channel back to the RC radio.
chan2_rawuint16_tusRC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan3_rawuint16_tusRC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan4_rawuint16_tusRC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan5_rawuint16_tusRC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan6_rawuint16_tusRC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan7_rawuint16_tusRC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan8_rawuint16_tusRC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio.
chan9_raw **uint16_tusRC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan10_raw **uint16_tusRC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan11_raw **uint16_tusRC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan12_raw **uint16_tusRC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan13_raw **uint16_tusRC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan14_raw **uint16_tusRC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan15_raw **uint16_tusRC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan16_raw **uint16_tusRC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan17_raw **uint16_tusRC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.
chan18_raw **uint16_tusRC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio.

MISSION_ITEM_INT ( #73 )

[Message] Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also https://mavlink.io/en/services/mission.html.

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. 0: false, 1: true. Set false to pause mission after the item completes.
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 )

[Message] Metrics typically displayed on a HUD for fixed wing aircraft.

Field NameTypeUnitsDescription
airspeedfloatm/sVehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed.
groundspeedfloatm/sCurrent ground speed.
headingint16_tdegCurrent heading in compass units (0-360, 0=north).
throttleuint16_t%Current throttle setting (0 to 100).
altfloatmCurrent altitude (MSL).
climbfloatm/sCurrent climb rate.

COMMAND_INT ( #75 )

[Message] Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html

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_tNot used.
autocontinueuint8_tNot used (set 0).
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 )

[Message] Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html

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 )

[Message] Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at https://mavlink.io/en/services/command.html

Field NameTypeUnitsValuesDescription
commanduint16_tMAV_CMDCommand ID (of acknowledged command).
resultuint8_tMAV_RESULTResult of command.
progress **uint8_t%The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown.
result_param2 **int32_tAdditional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate "unused" or "unknown").
target_system **uint8_tSystem ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
target_component **uint8_tComponent ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.

COMMAND_CANCEL ( #80 )

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

[Message] Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at https://mavlink.io/en/services/command.html

Field NameTypeValuesDescription
target_systemuint8_tSystem executing long running command. Should not be broadcast (0).
target_componentuint8_tComponent executing long running command.
commanduint16_tMAV_CMDCommand ID (of command to cancel).

MANUAL_SETPOINT ( #81 )

[Message] 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 )

[Message] Sets a desired vehicle attitude. 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
type_maskuint8_tATTITUDE_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
qfloat[4]Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD
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)
thrust_body **float[3]3D thrust setpoint in the body NED frame, normalized to -1 .. 1

ATTITUDE_TARGET ( #83 )

[Message] 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 NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
type_maskuint8_tATTITUDE_TARGET_TYPEMASKBitmap to indicate which dimensions should be ignored by the vehicle.
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 )

[Message] 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 )

[Message] 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 )

[Message] 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 )

[Message] 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 )

[Message] 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

[Message] 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 of 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 )

[Message] 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 of 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 )

[Message] 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 of 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 in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.

HIL_ACTUATOR_CONTROLS ( #93 )

[Message] 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 of the number.
controlsfloat[16]Control outputs -1 .. 1. Channel assignment depends on the simulated hardware.
modeuint8_tMAV_MODE_FLAGSystem mode. Includes arming state.
flagsuint64_tFlags as bitfield, 1: indicate simulation using lockstep.

OPTICAL_FLOW ( #100 )

[Message] 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 of the number.
sensor_iduint8_tSensor ID
flow_xint16_tdpixFlow in x-sensor direction
flow_yint16_tdpixFlow in y-sensor direction
flow_comp_m_xfloatm/sFlow in x-sensor direction, angular-speed compensated
flow_comp_m_yfloatm/sFlow 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 )

[Message] 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]Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
reset_counter **uint8_tEstimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.

VISION_POSITION_ESTIMATE ( #102 )

[Message] Local position/attitude estimate from a vision source.

Field NameTypeUnitsDescription
usecuint64_tusTimestamp (UNIX time or time since system boot)
xfloatmLocal X position
yfloatmLocal Y position
zfloatmLocal Z position
rollfloatradRoll angle
pitchfloatradPitch angle
yawfloatradYaw angle
covariance **float[21]Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
reset_counter **uint8_tEstimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.

VISION_SPEED_ESTIMATE ( #103 )

[Message] 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]Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
reset_counter **uint8_tEstimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.

VICON_POSITION_ESTIMATE ( #104 )

[Message] 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]Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.

HIGHRES_IMU ( #105 )

[Message] The IMU readings in SI units in NED body frame

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 of 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_pressurefloathPaAbsolute pressure
diff_pressurefloathPaDifferential pressure
pressure_altfloatAltitude calculated from pressure
temperaturefloatdegCTemperature
fields_updateduint16_tHIGHRES_IMU_UPDATED_FLAGSBitmap for fields that have updated since last message
id **uint8_tId. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)

OPTICAL_FLOW_RAD ( #106 )

[Message] 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 of 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 )

[Message] The IMU readings in SI units in NED body frame

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 of 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_pressurefloathPaAbsolute pressure
diff_pressurefloathPaDifferential pressure (airspeed)
pressure_altfloatAltitude calculated from pressure
temperaturefloatdegCTemperature
fields_updateduint32_tHIL_SENSOR_UPDATED_FLAGSBitmap for fields that have updated since last message
id **uint8_tSensor ID (zero indexed). Used for multiple sensor inputs

SIM_STATE ( #108 )

[Message] 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 (lower precision). Both this and the lat_int field should be set.
lonfloatdegLongitude (lower precision). Both this and the lon_int field should be set.
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
lat_int **int32_tdegE7Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).
lon_int **int32_tdegE7Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).

RADIO_STATUS ( #109 )

[Message] Status generated by radio and injected into MAVLink stream.

Field NameTypeUnitsDescription
rssiuint8_tLocal (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
remrssiuint8_tRemote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
txbufuint8_t%Remaining free transmitter buffer space.
noiseuint8_tLocal background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.
remnoiseuint8_tRemote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown.
rxerrorsuint16_tCount of radio packet receive errors (since boot).
fixeduint16_tCount of error corrected radio packets (since boot).

FILE_TRANSFER_PROTOCOL ( #110 )

[Message] File transfer protocol message: https://mavlink.io/en/services/ftp.html.

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 content/format of this block is defined in https://mavlink.io/en/services/ftp.html.

TIMESYNC ( #111 )

[Message] Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset.

Field NameTypeUnitsDescription
tc1int64_tnsTime sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component.
ts1int64_tnsTime sync timestamp 2. Timestamp of syncing component (mirrored in response).
target_system **uint8_tTarget system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component.
target_component **uint8_tTarget component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component.

CAMERA_TRIGGER ( #112 )

[Message] 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 of the number.
sequint32_tImage frame sequence

HIL_GPS ( #113 )

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

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 of 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_tGPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
epvuint16_tGPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
veluint16_tcm/sGPS ground speed. If unknown, set to: UINT16_MAX
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: UINT16_MAX
satellites_visibleuint8_tNumber of satellites visible. If unknown, set to UINT8_MAX
id **uint8_tGPS ID (zero indexed). Used for multiple GPS inputs
yaw **uint16_tcdegYaw of vehicle relative to Earth's North, zero means not available, use 36000 for north

HIL_OPTICAL_FLOW ( #114 )

[Message] 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 of 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 )

[Message] 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 of 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 )

[Message] 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_tmgaussX Magnetic field
ymagint16_tmgaussY Magnetic field
zmagint16_tmgaussZ Magnetic field
temperature **int16_tcdegCTemperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).

LOG_REQUEST_LIST ( #117 )

[Message] Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0.

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 )

[Message] 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 )

[Message] 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 )

[Message] 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 )

[Message] Erase all logs

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

LOG_REQUEST_END ( #122 )

[Message] Stop log transfer and resume normal logging

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

GPS_INJECT_DATA ( #123 )

DEPRECATED: Replaced by GPS_RTCM_DATA (2022-05).

[Message] 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 )

[Message] 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 of the number.
fix_typeuint8_tGPS_FIX_TYPEGPS fix type.
latint32_tdegE7Latitude (WGS84)
lonint32_tdegE7Longitude (WGS84)
altint32_tmmAltitude (MSL). Positive for up.
ephuint16_tGPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
epvuint16_tGPS VDOP vertical dilution of position (unitless * 100). 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 UINT8_MAX
dgps_numchuint8_tNumber of DGPS satellites
dgps_ageuint32_tmsAge of DGPS info
yaw **uint16_tcdegYaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
alt_ellipsoid **int32_tmmAltitude (above WGS84, EGM96 ellipsoid). Positive for up.
h_acc **uint32_tmmPosition uncertainty.
v_acc **uint32_tmmAltitude uncertainty.
vel_acc **uint32_tmmSpeed uncertainty.
hdg_acc **uint32_tdegE5Heading / track uncertainty

POWER_STATUS ( #125 )

[Message] 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 )

[Message] 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
target_system **uint8_tSystem ID
target_component **uint8_tComponent ID

GPS_RTK ( #127 )

[Message] 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 )

[Message] 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 )

[Message] 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_tmgaussX Magnetic field
ymagint16_tmgaussY Magnetic field
zmagint16_tmgaussZ Magnetic field
temperature **int16_tcdegCTemperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).

DATA_TRANSMISSION_HANDSHAKE ( #130 )

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

Field NameTypeUnitsValuesDescription
typeuint8_tMAVLINK_DATA_STREAM_TYPEType 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 )

[Message] Data packet for images sent using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.

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

DISTANCE_SENSOR ( #132 )

[Message] 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_tcm^2Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
horizontal_fov **floatradHorizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
vertical_fov **floatradVertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
quaternion **float[4]Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
signal_quality **uint8_t%Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.

TERRAIN_REQUEST ( #133 )

[Message] Request for terrain data and terrain status. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

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 )

[Message] Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

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 )

[Message] Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission.

Field NameTypeUnitsDescription
latint32_tdegE7Latitude
lonint32_tdegE7Longitude

TERRAIN_REPORT ( #136 )

[Message] Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: https://mavlink.io/en/services/terrain.html

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 )

[Message] Barometer readings for 2nd barometer

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
press_absfloathPaAbsolute pressure
press_difffloathPaDifferential pressure
temperatureint16_tcdegCAbsolute pressure temperature
temperature_press_diff **int16_tcdegCDifferential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.

ATT_POS_MOCAP ( #138 )

[Message] 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 of 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]Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.

SET_ACTUATOR_CONTROL_TARGET ( #139 )

[Message] 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 of 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 )

[Message] 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 of 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 )

[Message] 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 of 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 )

[Message] 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 )

[Message] Barometer readings for 3rd barometer

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
press_absfloathPaAbsolute pressure
press_difffloathPaDifferential pressure
temperatureint16_tcdegCAbsolute pressure temperature
temperature_press_diff **int16_tcdegCDifferential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.

FOLLOW_TARGET ( #144 )

[Message] 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](0 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 )

[Message] 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 of 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 )

[Message] Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO.

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 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1).
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
voltages_ext **uint16_t[4]mVBattery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
mode **uint8_tMAV_BATTERY_MODEBattery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
fault_bitmask **uint32_tMAV_BATTERY_FAULTFault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).

AUTOPILOT_VERSION ( #148 )

[Message] Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE.

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 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt
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 )

[Message] The location of a landing target. See: https://mavlink.io/en/services/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 of 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).

FENCE_STATUS ( #162 )

[Message] Status of geo-fencing. Sent in extended status stream when fencing enabled.

Field NameTypeUnitsValuesDescription
breach_statusuint8_tBreach status (0 if currently inside fence, 1 if outside).
breach_countuint16_tNumber of fence breaches.
breach_typeuint8_tFENCE_BREACHLast breach type.
breach_timeuint32_tmsTime (since boot) of last breach.
breach_mitigation **uint8_tFENCE_MITIGATEActive action to prevent fence breach

MAG_CAL_REPORT ( #192 )

[Message] Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.

Field NameTypeUnitsValuesDescription
compass_iduint8_tCompass being calibrated.
cal_maskuint8_tBitmask of compasses being calibrated.
cal_statusuint8_tMAG_CAL_STATUSCalibration Status.
autosaveduint8_t0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
fitnessfloatmgaussRMS milligauss residuals.
ofs_xfloatX offset.
ofs_yfloatY offset.
ofs_zfloatZ offset.
diag_xfloatX diagonal (matrix 11).
diag_yfloatY diagonal (matrix 22).
diag_zfloatZ diagonal (matrix 33).
offdiag_xfloatX off-diagonal (matrix 12 and 21).
offdiag_yfloatY off-diagonal (matrix 13 and 31).
offdiag_zfloatZ off-diagonal (matrix 32 and 23).
orientation_confidence **floatConfidence in orientation (higher is better).
old_orientation **uint8_tMAV_SENSOR_ORIENTATIONorientation before calibration.
new_orientation **uint8_tMAV_SENSOR_ORIENTATIONorientation after calibration.
scale_factor **floatfield radius correction factor

EFI_STATUS ( #225 )

[Message] EFI status output

Field NameTypeUnitsDescription
healthuint8_tEFI health status
ecu_indexfloatECU index
rpmfloatRPM
fuel_consumedfloatcm^3Fuel consumed
fuel_flowfloatcm^3/minFuel flow rate
engine_loadfloat%Engine load
throttle_positionfloat%Throttle position
spark_dwell_timefloatmsSpark dwell time
barometric_pressurefloatkPaBarometric pressure
intake_manifold_pressurefloatkPaIntake manifold pressure(
intake_manifold_temperaturefloatdegCIntake manifold temperature
cylinder_head_temperaturefloatdegCCylinder head temperature
ignition_timingfloatdegIgnition timing (Crank angle degrees)
injection_timefloatmsInjection time
exhaust_gas_temperaturefloatdegCExhaust gas temperature
throttle_outfloat%Output throttle
pt_compensationfloatPressure/temperature compensation
ignition_voltage **floatVSupply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.
fuel_pressure **floatkPaFuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.

ESTIMATOR_STATUS ( #230 )

[Message] 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 of 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 )

[Message] Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD).

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 of the number.
wind_xfloatm/sWind in North (NED) direction (NAN if unknown)
wind_yfloatm/sWind in East (NED) direction (NAN if unknown)
wind_zfloatm/sWind in down (NED) direction (NAN if unknown)
var_horizfloatm/sVariability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)
var_vertfloatm/sVariability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)
wind_altfloatmAltitude (MSL) that this measurement was taken at (NAN if unknown)
horiz_accuracyfloatm/sHorizontal speed 1-STD accuracy (0 if unknown)
vert_accuracyfloatm/sVertical speed 1-STD accuracy (0 if unknown)

GPS_INPUT ( #232 )

[Message] 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 of 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.
hdopfloatGPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
vdopfloatGPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
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.
yaw **uint16_tcdegYaw of vehicle relative to Earth's North, zero means not available, use 36000 for north

GPS_RTCM_DATA ( #233 )

[Message] 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 )

DEPRECATED: Replaced by HIGH_LATENCY2 (2020-10).

[Message] 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 UINT8_MAX
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 )

[Message] 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. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
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 level (-1 if field not provided).
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 )

[Message] 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 of 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 )

[Message] Contains the home position. The home position is the default position that the system will return to and land on. The position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command).

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 (NED)
yfloatmLocal Y position of this position in the local coordinate frame (NED)
zfloatmLocal Z position of this position in the local coordinate frame (NED: positive "down")
qfloat[4]Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied.
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 of the number.

SET_HOME_POSITION ( #243 )

DEPRECATED: Replaced by MAV_CMD_DO_SET_HOME (2022-02). The command protocol version (MAV_CMD_DO_SET_HOME) allows a GCS to detect when setting the home position has failed.

[Message] Sets the home position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).

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 (NED)
yfloatmLocal Y position of this position in the local coordinate frame (NED)
zfloatmLocal Z position of this position in the local coordinate frame (NED: positive "down")
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 of the number.

MESSAGE_INTERVAL ( #244 )

[Message] The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. This interface replaces DATA_STREAM.

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 )

[Message] 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 )

[Message] 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 )

[Message] 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] 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/definition_files/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 must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand 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 )

[Message] 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 )

[Message] 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 of the number.
xfloatx
yfloaty
zfloatz

NAMED_VALUE_FLOAT ( #251 )

[Message] 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 )

[Message] 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 )

[Message] 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
id **uint16_tUnique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
chunk_seq **uint8_tThis chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.

DEBUG ( #254 )

[Message] 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 )

[Message] (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 )

[Message] (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 )

DEPRECATED: Replaced by PLAY_TUNE_V2 (2019-10). New version explicitly defines format. More interoperable.

[Message] (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 )

[Message] (MAVLink 2) Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.

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, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff). Use 0 if not known.
focal_lengthfloatmmFocal length. Use NaN if not known.
sensor_size_hfloatmmImage sensor size horizontal. Use NaN if not known.
sensor_size_vfloatmmImage sensor size vertical. Use NaN if not known.
resolution_huint16_tpixHorizontal image resolution. Use 0 if not known.
resolution_vuint16_tpixVertical image resolution. Use 0 if not known.
lens_iduint8_tReserved for a lens ID. Use 0 if not known.
flagsuint32_tCAMERA_CAP_FLAGSBitmap of camera capability flags.
cam_definition_versionuint16_tCamera definition version (iteration). Use 0 if not known.
cam_definition_urichar[140]Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known.
gimbal_device_id **uint8_tGimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera.

CAMERA_SETTINGS ( #260 )

[Message] (MAVLink 2) Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
mode_iduint8_tCAMERA_MODECamera mode
zoomLevel **floatCurrent zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)
focusLevel **floatCurrent focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)

STORAGE_INFORMATION ( #261 )

[Message] (MAVLink 2) Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc.

Field NameTypeUnitsValuesDescription
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_tSTORAGE_STATUSStatus of storage
total_capacityfloatMiBTotal capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
used_capacityfloatMiBUsed capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
available_capacityfloatMiBAvailable storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
read_speedfloatMiB/sRead speed.
write_speedfloatMiB/sWrite speed.
type **uint8_tSTORAGE_TYPEType of storage
name **char[32]Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.
storage_usage **uint8_tSTORAGE_USAGE_FLAGFlags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.

CAMERA_CAPTURE_STATUS ( #262 )

[Message] (MAVLink 2) Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.

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_tmsElapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy.
available_capacityfloatMiBAvailable storage capacity.
image_count **int32_tTotal number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).

CAMERA_IMAGE_CAPTURED ( #263 )

[Message] (MAVLink 2) Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
time_utcuint64_tusTimestamp (time since UNIX epoch) in UTC. 0 for unknown.
camera_iduint8_tDeprecated/unused. Component IDs are used to differentiate multiple cameras.
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 1, 0, 0, 0)
image_indexint32_tZero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -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 )

[Message] (MAVLink 2) Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
arming_time_utcuint64_tusTimestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC.
takeoff_time_utcuint64_tusTimestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC.
flight_uuiduint64_tFlight number. Note, field is misnamed UUID.
landing_time **uint32_tmsTimestamp at landing (in ms since system boot). Set to 0 at boot and on arming.

MOUNT_ORIENTATION ( #265 )

DEPRECATED: Replaced by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW (2020-01). This message is being superseded by MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW. The message can still be used to communicate with legacy gimbals implementing it.

[Message] (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 relative to Earth's North, north is 0 (set to NaN for invalid).

LOGGING_DATA ( #266 )

[Message] (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 UINT8_MAX if no start exists).
datauint8_t[249]logged data

LOGGING_DATA_ACKED ( #267 )

[Message] (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 UINT8_MAX if no start exists).
datauint8_t[249]logged data

LOGGING_ACK ( #268 )

[Message] (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 )

[Message] (MAVLink 2) Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc.

Field NameTypeUnitsValuesDescription
stream_iduint8_tVideo Stream ID (1 for first, 2 for second, etc.)
countuint8_tNumber of streams available.
typeuint8_tVIDEO_STREAM_TYPEType of stream.
flagsuint16_tVIDEO_STREAM_STATUS_FLAGSBitmap of stream status flags.
frameratefloatHzFrame rate.
resolution_huint16_tpixHorizontal resolution.
resolution_vuint16_tpixVertical resolution.
bitrateuint32_tbits/sBit rate.
rotationuint16_tdegVideo image rotation clockwise.
hfovuint16_tdegHorizontal Field of view.
namechar[32]Stream name.
urichar[160]Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).

VIDEO_STREAM_STATUS ( #270 )

[Message] (MAVLink 2) Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE.

Field NameTypeUnitsValuesDescription
stream_iduint8_tVideo Stream ID (1 for first, 2 for second, etc.)
flagsuint16_tVIDEO_STREAM_STATUS_FLAGSBitmap of stream status flags
frameratefloatHzFrame rate
resolution_huint16_tpixHorizontal resolution
resolution_vuint16_tpixVertical resolution
bitrateuint32_tbits/sBit rate
rotationuint16_tdegVideo image rotation clockwise
hfovuint16_tdegHorizontal Field of view

CAMERA_FOV_STATUS ( #271 )

[Message] (MAVLink 2) Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
lat_cameraint32_tdegE7Latitude of camera (INT32_MAX if unknown).
lon_cameraint32_tdegE7Longitude of camera (INT32_MAX if unknown).
alt_cameraint32_tmmAltitude (MSL) of camera (INT32_MAX if unknown).
lat_imageint32_tdegE7Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
lon_imageint32_tdegE7Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
alt_imageint32_tmmAltitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
qfloat[4]Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
hfovfloatdegHorizontal field of view (NaN if unknown).
vfovfloatdegVertical field of view (NaN if unknown).

CAMERA_TRACKING_IMAGE_STATUS ( #275 )

[Message] (MAVLink 2) Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.

Field NameTypeValuesDescription
tracking_statusuint8_tCAMERA_TRACKING_STATUS_FLAGSCurrent tracking status
tracking_modeuint8_tCAMERA_TRACKING_MODECurrent tracking mode
target_datauint8_tCAMERA_TRACKING_TARGET_DATADefines location of target data
point_xfloatCurrent tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
point_yfloatCurrent tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
radiusfloatCurrent tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
rec_top_xfloatCurrent tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
rec_top_yfloatCurrent tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
rec_bottom_xfloatCurrent tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
rec_bottom_yfloatCurrent tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown

CAMERA_TRACKING_GEO_STATUS ( #276 )

[Message] (MAVLink 2) Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval.

Field NameTypeUnitsValuesDescription
tracking_statusuint8_tCAMERA_TRACKING_STATUS_FLAGSCurrent tracking status
latint32_tdegE7Latitude of tracked object
lonint32_tdegE7Longitude of tracked object
altfloatmAltitude of tracked object(AMSL, WGS84)
h_accfloatmHorizontal accuracy. NAN if unknown
v_accfloatmVertical accuracy. NAN if unknown
vel_nfloatm/sNorth velocity of tracked object. NAN if unknown
vel_efloatm/sEast velocity of tracked object. NAN if unknown
vel_dfloatm/sDown velocity of tracked object. NAN if unknown
vel_accfloatm/sVelocity accuracy. NAN if unknown
distfloatmDistance between camera and tracked object. NAN if unknown
hdgfloatradHeading in radians, in NED. NAN if unknown
hdg_accfloatradAccuracy of heading, in NED. NAN if unknown

GIMBAL_MANAGER_INFORMATION ( #280 )

[Message] (MAVLink 2) Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE.

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
cap_flagsuint32_tGIMBAL_MANAGER_CAP_FLAGSBitmap of gimbal capability flags.
gimbal_device_iduint8_tGimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).
roll_minfloatradMinimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
roll_maxfloatradMaximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
pitch_minfloatradMinimum pitch angle (positive: up, negative: down)
pitch_maxfloatradMaximum pitch angle (positive: up, negative: down)
yaw_minfloatradMinimum yaw angle (positive: to the right, negative: to the left)
yaw_maxfloatradMaximum yaw angle (positive: to the right, negative: to the left)

GIMBAL_MANAGER_STATUS ( #281 )

[Message] (MAVLink 2) Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz).

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
flagsuint32_tGIMBAL_MANAGER_FLAGSHigh level gimbal manager flags currently applied.
gimbal_device_iduint8_tGimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal).
primary_control_sysiduint8_tSystem ID of MAVLink component with primary control, 0 for none.
primary_control_compiduint8_tComponent ID of MAVLink component with primary control, 0 for none.
secondary_control_sysiduint8_tSystem ID of MAVLink component with secondary control, 0 for none.
secondary_control_compiduint8_tComponent ID of MAVLink component with secondary control, 0 for none.

GIMBAL_MANAGER_SET_ATTITUDE ( #282 )

[Message] (MAVLink 2) High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
flagsuint32_tGIMBAL_MANAGER_FLAGSHigh level gimbal manager flags to use.
gimbal_device_iduint8_tComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
qfloat[4]Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
angular_velocity_xfloatrad/sX component of angular velocity, positive is rolling to the right, NaN to be ignored.
angular_velocity_yfloatrad/sY component of angular velocity, positive is pitching up, NaN to be ignored.
angular_velocity_zfloatrad/sZ component of angular velocity, positive is yawing to the right, NaN to be ignored.

GIMBAL_DEVICE_INFORMATION ( #283 )

[Message] (MAVLink 2) Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc..

Field NameTypeUnitsValuesDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
vendor_namechar[32]Name of the gimbal vendor.
model_namechar[32]Name of the gimbal model.
custom_namechar[32]Custom name of the gimbal given to it by the user.
firmware_versionuint32_tVersion of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
hardware_versionuint32_tVersion of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
uiduint64_tUID of gimbal hardware (0 if unknown).
cap_flagsuint16_tGIMBAL_DEVICE_CAP_FLAGSBitmap of gimbal capability flags.
custom_cap_flagsuint16_tBitmap for use for gimbal-specific capability flags.
roll_minfloatradMinimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
roll_maxfloatradMaximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.
pitch_minfloatradMinimum hardware pitch angle (positive: up, negative: down). NAN if unknown.
pitch_maxfloatradMaximum hardware pitch angle (positive: up, negative: down). NAN if unknown.
yaw_minfloatradMinimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
yaw_maxfloatradMaximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
gimbal_device_id **uint8_tThis field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.

GIMBAL_DEVICE_SET_ATTITUDE ( #284 )

[Message] (MAVLink 2) Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. The quaternion and angular velocities can be set to NaN according to use case. For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. These rules are to ensure backwards compatibility. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
flagsuint16_tGIMBAL_DEVICE_FLAGSLow level gimbal flags.
qfloat[4]Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored.
angular_velocity_xfloatrad/sX component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored.
angular_velocity_yfloatrad/sY component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored.
angular_velocity_zfloatrad/sZ component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.

GIMBAL_DEVICE_ATTITUDE_STATUS ( #285 )

[Message] (MAVLink 2) Message reporting the status of a gimbal device. This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). For the angles encoded in the quaternion and the angular velocities holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). If neither of these flags are set, then (for backwards compatibility) it holds: If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), else they are relative to the vehicle heading (vehicle frame). Other conditions of the flags are not allowed. The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
time_boot_msuint32_tmsTimestamp (time since system boot).
flagsuint16_tGIMBAL_DEVICE_FLAGSCurrent gimbal flags set.
qfloat[4]Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description.
angular_velocity_xfloatrad/sX component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown.
angular_velocity_yfloatrad/sY component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown.
angular_velocity_zfloatrad/sZ component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown.
failure_flagsuint32_tGIMBAL_DEVICE_ERROR_FLAGSFailure flags (0 for no failure)
delta_yaw **floatradYaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown.
delta_yaw_velocity **floatrad/sYaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.
gimbal_device_id **uint8_tThis field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.

AUTOPILOT_STATE_FOR_GIMBAL_DEVICE ( #286 )

[Message] (MAVLink 2) Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
time_boot_usuint64_tusTimestamp (time since system boot).
qfloat[4]Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).
q_estimated_delay_usuint32_tusEstimated delay of the attitude data. 0 if unknown.
vxfloatm/sX Speed in NED (North, East, Down). NAN if unknown.
vyfloatm/sY Speed in NED (North, East, Down). NAN if unknown.
vzfloatm/sZ Speed in NED (North, East, Down). NAN if unknown.
v_estimated_delay_usuint32_tusEstimated delay of the speed data. 0 if unknown.
feed_forward_angular_velocity_zfloatrad/sFeed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing.
estimator_statusuint16_tESTIMATOR_STATUS_FLAGSBitmap indicating which estimator outputs are valid.
landed_stateuint8_tMAV_LANDED_STATEThe landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
angular_velocity_z **floatrad/sZ component of angular velocity in NED (North, East, Down). NaN if unknown.

GIMBAL_MANAGER_SET_PITCHYAW ( #287 )

[Message] (MAVLink 2) Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
flagsuint32_tGIMBAL_MANAGER_FLAGSHigh level gimbal manager flags to use.
gimbal_device_iduint8_tComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
pitchfloatradPitch angle (positive: up, negative: down, NaN to be ignored).
yawfloatradYaw angle (positive: to the right, negative: to the left, NaN to be ignored).
pitch_ratefloatrad/sPitch angular rate (positive: up, negative: down, NaN to be ignored).
yaw_ratefloatrad/sYaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).

GIMBAL_MANAGER_SET_MANUAL_CONTROL ( #288 )

[Message] (MAVLink 2) High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
flagsuint32_tGIMBAL_MANAGER_FLAGSHigh level gimbal manager flags.
gimbal_device_iduint8_tComponent ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
pitchfloatPitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
yawfloatYaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
pitch_ratefloatPitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).
yaw_ratefloatYaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).

ESC_INFO ( #290 )

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

[Message] (MAVLink 2) ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data.

Field NameTypeUnitsValuesDescription
indexuint8_tIndex of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
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.
counteruint16_tCounter of data packets received.
countuint8_tTotal number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
connection_typeuint8_tESC_CONNECTION_TYPEConnection type protocol for all ESC.
infouint8_tInformation regarding online/offline status of each ESC.
failure_flagsuint16_t[4]ESC_FAILURE_FLAGSBitmap of ESC failure flags.
error_countuint32_t[4]Number of reported errors by each ESC since boot.
temperatureint16_t[4]cdegCTemperature of each ESC. INT16_MAX: if data not supplied by ESC.

ESC_STATUS ( #291 )

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

[Message] (MAVLink 2) ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer).

Field NameTypeUnitsDescription
indexuint8_tIndex of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
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.
rpmint32_t[4]rpmReported motor RPM from each ESC (negative for reverse rotation).
voltagefloat[4]VVoltage measured from each ESC.
currentfloat[4]ACurrent measured from each ESC.

WIFI_CONFIG_AP ( #299 )

[Message] (MAVLink 2) Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE

Field NameTypeValuesDescription
ssidchar[32]Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response.
passwordchar[64]Password. Blank for an open AP. MD5 hash when message is sent back as a response.
mode **int8_tWIFI_CONFIG_AP_MODEWiFi Mode.
response **int8_tWIFI_CONFIG_AP_RESPONSEMessage acceptance response (sent back to GS).

AIS_VESSEL ( #301 )

[Message] (MAVLink 2) The location and information of an AIS vessel

Field NameTypeUnitsValuesDescription
MMSIuint32_tMobile Marine Service Identifier, 9 decimal digits
latint32_tdegE7Latitude
lonint32_tdegE7Longitude
COGuint16_tcdegCourse over ground
headinguint16_tcdegTrue heading
velocityuint16_tcm/sSpeed over ground
turn_rateint8_tcdeg/sTurn rate
navigational_statusuint8_tAIS_NAV_STATUSNavigational status
typeuint8_tAIS_TYPEType of vessels
dimension_bowuint16_tmDistance from lat/lon location to bow
dimension_sternuint16_tmDistance from lat/lon location to stern
dimension_portuint8_tmDistance from lat/lon location to port side
dimension_starboarduint8_tmDistance from lat/lon location to starboard side
callsignchar[7]The vessel callsign
namechar[20]The vessel name
tslcuint16_tsTime since last communication in seconds
flagsuint16_tAIS_FLAGSBitmask to indicate various statuses including valid data fields

UAVCAN_NODE_STATUS ( #310 )

[Message] (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 of 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 )

[Message] (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 of 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). 0 if unknown.

PARAM_EXT_REQUEST_READ ( #320 )

[Message] (MAVLink 2) Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response.

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 )

[Message] (MAVLink 2) Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID

PARAM_EXT_VALUE ( #322 )

[Message] (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 )

[Message] (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 )

[Message] (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 )

[Message] (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 of the number.
sensor_typeuint8_tMAV_DISTANCE_SENSORClass id of the distance sensor type.
distancesuint16_t[72]cmDistance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching 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. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
min_distanceuint16_tcmMinimum distance the sensor can measure.
max_distanceuint16_tcmMaximum distance the sensor can measure.
increment_f **floatdegAngular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.
angle_offset **floatdegRelative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.
frame **uint8_tMAV_FRAMECoordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.

ODOMETRY ( #331 )

[Message] (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 of 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]Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
velocity_covariancefloat[21]Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
reset_counter **uint8_tEstimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
estimator_type **uint8_tMAV_ESTIMATOR_TYPEType of estimator that is providing the odometry.
quality **int8_t%Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality

TRAJECTORY_REPRESENTATION_WAYPOINTS ( #332 )

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

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 of 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
commanduint16_t[5]MAV_CMDMAV_CMD command id of waypoint, set to UINT16_MAX if not being used.

TRAJECTORY_REPRESENTATION_BEZIER ( #333 )

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

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 of the number.
valid_pointsuint8_tNumber of valid control points (up-to 5 points are possible)
pos_xfloat[5]mX-coordinate of bezier control points. Set to NaN if not being used
pos_yfloat[5]mY-coordinate of bezier control points. Set to NaN if not being used
pos_zfloat[5]mZ-coordinate of bezier control points. 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

CELLULAR_STATUS ( #334 )

[Message] (MAVLink 2) Report current used cellular network status

Field NameTypeValuesDescription
statusuint8_tCELLULAR_STATUS_FLAGCellular modem status
failure_reasonuint8_tCELLULAR_NETWORK_FAILED_REASONFailure reason when status in in CELLULAR_STATUS_FLAG_FAILED
typeuint8_tCELLULAR_NETWORK_RADIO_TYPECellular network radio type: gsm, cdma, lte...
qualityuint8_tSignal quality in percent. If unknown, set to UINT8_MAX
mccuint16_tMobile country code. If unknown, set to UINT16_MAX
mncuint16_tMobile network code. If unknown, set to UINT16_MAX
lacuint16_tLocation area code. If unknown, set to 0

[Message] (MAVLink 2) Status of the Iridium SBD link.

Field NameTypeUnitsDescription
timestampuint64_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 of the number.
last_heartbeatuint64_tusTimestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
failed_sessionsuint16_tNumber of failed SBD sessions.
successful_sessionsuint16_tNumber of successful SBD sessions.
signal_qualityuint8_tSignal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.
ring_pendinguint8_t1: Ring call pending, 0: No call pending.
tx_session_pendinguint8_t1: Transmission session pending, 0: No transmission session pending.
rx_session_pendinguint8_t1: Receiving session pending, 0: No receiving session pending.

CELLULAR_CONFIG ( #336 )

[Message] (MAVLink 2) Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE.

Field NameTypeValuesDescription
enable_lteuint8_tEnable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
enable_pinuint8_tEnable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
pinchar[16]PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.
new_pinchar[16]New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.
apnchar[32]Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.
pukchar[16]Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.
roaminguint8_tEnable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
responseuint8_tCELLULAR_CONFIG_RESPONSEMessage acceptance response (sent back to GS).

RAW_RPM ( #339 )

[Message] (MAVLink 2) RPM sensor data message.

Field NameTypeUnitsDescription
indexuint8_tIndex of this RPM sensor (0-indexed)
frequencyfloatrpmIndicated rate

UTM_GLOBAL_POSITION ( #340 )

[Message] (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_tcsTime 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 )

[Message] (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 of 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).

[Message] (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 of 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.

BATTERY_INFO ( #370 )

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

[Message] (MAVLink 2) Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information.

Field NameTypeUnitsValuesDescription
iduint8_tBattery ID
battery_functionuint8_tMAV_BATTERY_FUNCTIONFunction of the battery.
typeuint8_tMAV_BATTERY_TYPEType (chemistry) of the battery.
state_of_healthuint8_t%State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided.
cells_in_seriesuint8_tNumber of battery cells in series. 0: field not provided.
cycle_countuint16_tLifetime count of the number of charge/discharge cycles (https://en.wikipedia.org/wiki/Charge_cycle). UINT16_MAX: field not provided.
weightuint16_tgBattery weight. 0: field not provided.
discharge_minimum_voltagefloatVMinimum per-cell voltage when discharging. 0: field not provided.
charging_minimum_voltagefloatVMinimum per-cell voltage when charging. 0: field not provided.
resting_minimum_voltagefloatVMinimum per-cell voltage when resting. 0: field not provided.
charging_maximum_voltagefloatVMaximum per-cell voltage when charged. 0: field not provided.
charging_maximum_currentfloatAMaximum pack continuous charge current. 0: field not provided.
nominal_voltagefloatVBattery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided.
discharge_maximum_currentfloatAMaximum pack discharge current. 0: field not provided.
discharge_maximum_burst_currentfloatAMaximum pack discharge burst current. 0: field not provided.
design_capacityfloatAhFully charged design capacity. 0: field not provided.
full_charge_capacityfloatAhPredicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided.
manufacture_datechar[9]Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided.
serial_numberchar[32]Serial number in ASCII characters, 0 terminated. All 0: field not provided.
namechar[50]Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided.

GENERATOR_STATUS ( #373 )

[Message] (MAVLink 2) Telemetry of power generation system. Alternator or mechanical generator.

Field NameTypeUnitsValuesDescription
statusuint64_tMAV_GENERATOR_STATUS_FLAGStatus flags.
generator_speeduint16_trpmSpeed of electrical generator or alternator. UINT16_MAX: field not provided.
battery_currentfloatACurrent into/out of battery. Positive for out. Negative for in. NaN: field not provided.
load_currentfloatACurrent going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
power_generatedfloatWThe power being generated. NaN: field not provided
bus_voltagefloatVVoltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
rectifier_temperatureint16_tdegCThe temperature of the rectifier or power converter. INT16_MAX: field not provided.
bat_current_setpointfloatAThe target battery current. Positive for out. Negative for in. NaN: field not provided
generator_temperatureint16_tdegCThe temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.
runtimeuint32_tsSeconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
time_until_maintenanceint32_tsSeconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.

ACTUATOR_OUTPUT_STATUS ( #375 )

[Message] (MAVLink 2) The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (since system boot).
activeuint32_tActive outputs
actuatorfloat[32]Servo / motor output array values. Zero values indicate unused channels.

TIME_ESTIMATE_TO_TARGET ( #380 )

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

[Message] (MAVLink 2) Time/duration estimates for various events and actions given the current vehicle state and position.

Field NameTypeUnitsDescription
safe_returnint32_tsEstimated time to complete the vehicle's configured "safe return" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available.
landint32_tsEstimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available.
mission_next_itemint32_tsEstimated time for reaching/completing the currently active mission item. -1 means no time estimate available.
mission_endint32_tsEstimated time for completing the current mission. -1 means no mission active and/or no estimate available.
commanded_actionint32_tsEstimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available.

TUNNEL ( #385 )

[Message] (MAVLink 2) Message for transporting "arbitrary" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID (can be 0 for broadcast, but this is discouraged)
target_componentuint8_tComponent ID (can be 0 for broadcast, but this is discouraged)
payload_typeuint16_tMAV_TUNNEL_PAYLOAD_TYPEA code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
payload_lengthuint8_tLength of the data transported in payload
payloaduint8_t[128]Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type.

CAN_FRAME ( #386 )

[Message] (MAVLink 2) A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
busuint8_tBus number
lenuint8_tFrame length
iduint32_tFrame ID
datauint8_t[8]Frame data

ONBOARD_COMPUTER_STATUS ( #390 )

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

[Message] (MAVLink 2) Hardware status sent by an onboard computer.

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 of the number.
uptimeuint32_tmsTime since system boot.
typeuint8_tType of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.
cpu_coresuint8_t[8]CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
cpu_combineduint8_t[10]Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
gpu_coresuint8_t[4]GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
gpu_combineduint8_t[10]Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
temperature_boardint8_tdegCTemperature of the board. A value of INT8_MAX implies the field is unused.
temperature_coreint8_t[8]degCTemperature of the CPU core. A value of INT8_MAX implies the field is unused.
fan_speedint16_t[4]rpmFan speeds. A value of INT16_MAX implies the field is unused.
ram_usageuint32_tMiBAmount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.
ram_totaluint32_tMiBTotal amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.
storage_typeuint32_t[4]Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.
storage_usageuint32_t[4]MiBAmount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.
storage_totaluint32_t[4]MiBTotal amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.
link_typeuint32_t[6]Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
link_tx_rateuint32_t[6]KiB/sNetwork traffic from the component system. A value of UINT32_MAX implies the field is unused.
link_rx_rateuint32_t[6]KiB/sNetwork traffic to the component system. A value of UINT32_MAX implies the field is unused.
link_tx_maxuint32_t[6]KiB/sNetwork capacity from the component system. A value of UINT32_MAX implies the field is unused.
link_rx_maxuint32_t[6]KiB/sNetwork capacity to the component system. A value of UINT32_MAX implies the field is unused.

COMPONENT_INFORMATION ( #395 )

DEPRECATED: Replaced by COMPONENT_METADATA (2022-04).

[Message] (MAVLink 2) Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
general_metadata_file_crcuint32_tCRC32 of the general metadata file (general_metadata_uri).
general_metadata_urichar[100]MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.
peripherals_metadata_file_crcuint32_tCRC32 of peripherals metadata file (peripherals_metadata_uri).
peripherals_metadata_urichar[100](Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about "attached components" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated.

COMPONENT_METADATA ( #397 )

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

[Message] (MAVLink 2) Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: https://mavlink.io/en/services/component_information.html. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION.

Field NameTypeUnitsDescription
time_boot_msuint32_tmsTimestamp (time since system boot).
file_crcuint32_tCRC32 of the general metadata file.
urichar[100]MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated.

PLAY_TUNE_V2 ( #400 )

[Message] (MAVLink 2) Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
formatuint32_tTUNE_FORMATTune format
tunechar[248]Tune definition as a NULL-terminated string.

SUPPORTED_TUNES ( #401 )

[Message] (MAVLink 2) Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
formatuint32_tTUNE_FORMATBitfield of supported tune formats.

EVENT ( #410 )

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

[Message] (MAVLink 2) Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component).

Field NameTypeUnitsDescription
destination_componentuint8_tComponent ID
destination_systemuint8_tSystem ID
iduint32_tEvent ID (as defined in the component metadata)
event_time_boot_msuint32_tmsTimestamp (time since system boot when the event happened).
sequenceuint16_tSequence number.
log_levelsuint8_tLog levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9
argumentsuint8_t[40]Arguments (depend on event ID).

CURRENT_EVENT_SEQUENCE ( #411 )

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

[Message] (MAVLink 2) Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events.

Field NameTypeValuesDescription
sequenceuint16_tSequence number.
flagsuint8_tMAV_EVENT_CURRENT_SEQUENCE_FLAGSFlag bitset.

REQUEST_EVENT ( #412 )

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

[Message] (MAVLink 2) Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response.

Field NameTypeDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
first_sequenceuint16_tFirst sequence number of the requested event.
last_sequenceuint16_tLast sequence number of the requested event.

RESPONSE_EVENT_ERROR ( #413 )

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

[Message] (MAVLink 2) Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore).

Field NameTypeValuesDescription
target_systemuint8_tSystem ID
target_componentuint8_tComponent ID
sequenceuint16_tSequence number.
sequence_oldest_availableuint16_tOldest Sequence number that is still available after the sequence set in REQUEST_EVENT.
reasonuint8_tMAV_EVENT_ERROR_REASONError reason.

CANFD_FRAME ( #387 )

[Message] (MAVLink 2) A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
busuint8_tbus number
lenuint8_tFrame length
iduint32_tFrame ID
datauint8_t[64]Frame data

CAN_FILTER_MODIFY ( #388 )

[Message] (MAVLink 2) Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
busuint8_tbus number
operationuint8_tCAN_FILTER_OPwhat operation to perform on the filter list. See CAN_FILTER_OP enum.
num_idsuint8_tnumber of IDs in filter list
idsuint16_t[16]filter IDs, length num_ids

WHEEL_DISTANCE ( #9000 )

[Message] (MAVLink 2) Cumulative distance traveled for each reported wheel.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (synced to UNIX time or since system boot).
countuint8_tNumber of wheels reported.
distancedouble[16]mDistance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints.

WINCH_STATUS ( #9005 )

[Message] (MAVLink 2) Winch status.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusTimestamp (synced to UNIX time or since system boot).
line_lengthfloatmLength of line released. NaN if unknown
speedfloatm/sSpeed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown
tensionfloatkgTension on the line. NaN if unknown
voltagefloatVVoltage of the battery supplying the winch. NaN if unknown
currentfloatACurrent draw from the winch. NaN if unknown
temperatureint16_tdegCTemperature of the motor. INT16_MAX if unknown
statusuint32_tMAV_WINCH_STATUS_FLAGStatus flags

OPEN_DRONE_ID_BASIC_ID ( #12900 )

[Message] (MAVLink 2) Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. https://github.com/opendroneid/opendroneid-core-c. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at https://mavlink.io/en/services/opendroneid.html.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
id_typeuint8_tMAV_ODID_ID_TYPEIndicates the format for the uas_id field of this message.
ua_typeuint8_tMAV_ODID_UA_TYPEIndicates the type of UA (Unmanned Aircraft).
uas_iduint8_t[20]UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.

OPEN_DRONE_ID_LOCATION ( #12901 )

[Message] (MAVLink 2) Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
statusuint8_tMAV_ODID_STATUSIndicates whether the unmanned aircraft is on the ground or in the air.
directionuint16_tcdegDirection over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.
speed_horizontaluint16_tcm/sGround speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.
speed_verticalint16_tcm/sThe vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.
latitudeint32_tdegE7Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
longitudeint32_tdegE7Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
altitude_barometricfloatmThe altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
altitude_geodeticfloatmThe geodetic altitude as defined by WGS84. If unknown: -1000 m.
height_referenceuint8_tMAV_ODID_HEIGHT_REFIndicates the reference point for the height field.
heightfloatmThe current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.
horizontal_accuracyuint8_tMAV_ODID_HOR_ACCThe accuracy of the horizontal position.
vertical_accuracyuint8_tMAV_ODID_VER_ACCThe accuracy of the vertical position.
barometer_accuracyuint8_tMAV_ODID_VER_ACCThe accuracy of the barometric altitude.
speed_accuracyuint8_tMAV_ODID_SPEED_ACCThe accuracy of the horizontal and vertical speed.
timestampfloatsSeconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF.
timestamp_accuracyuint8_tMAV_ODID_TIME_ACCThe accuracy of the timestamps.

OPEN_DRONE_ID_AUTHENTICATION ( #12902 )

[Message] (MAVLink 2) Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
authentication_typeuint8_tMAV_ODID_AUTH_TYPEIndicates the type of authentication.
data_pageuint8_tAllowed range is 0 - 15.
last_page_indexuint8_tThis field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.
lengthuint8_tbytesThis field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h.
timestampuint32_tsThis field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
authentication_datauint8_t[23]Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.

OPEN_DRONE_ID_SELF_ID ( #12903 )

[Message] (MAVLink 2) Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
description_typeuint8_tMAV_ODID_DESC_TYPEIndicates the type of the description field.
descriptionchar[23]Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.

OPEN_DRONE_ID_SYSTEM ( #12904 )

[Message] (MAVLink 2) Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information.

Field NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
operator_location_typeuint8_tMAV_ODID_OPERATOR_LOCATION_TYPESpecifies the operator location type.
classification_typeuint8_tMAV_ODID_CLASSIFICATION_TYPESpecifies the classification type of the UA.
operator_latitudeint32_tdegE7Latitude of the operator. If unknown: 0 (both Lat/Lon).
operator_longitudeint32_tdegE7Longitude of the operator. If unknown: 0 (both Lat/Lon).
area_countuint16_tNumber of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA.
area_radiusuint16_tmRadius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA.
area_ceilingfloatmArea Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.
area_floorfloatmArea Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA.
category_euuint8_tMAV_ODID_CATEGORY_EUWhen classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
class_euuint8_tMAV_ODID_CLASS_EUWhen classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
operator_altitude_geofloatmGeodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
timestampuint32_ts32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.

OPEN_DRONE_ID_OPERATOR_ID ( #12905 )

[Message] (MAVLink 2) Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
operator_id_typeuint8_tMAV_ODID_OPERATOR_ID_TYPEIndicates the type of the operator_id field.
operator_idchar[20]Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.

OPEN_DRONE_ID_MESSAGE_PACK ( #12915 )

[Message] (MAVLink 2) An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
id_or_macuint8_t[20]Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
single_message_sizeuint8_tbytesThis field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length.
msg_pack_sizeuint8_tNumber of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.
messagesuint8_t[225]Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.

OPEN_DRONE_ID_ARM_STATUS ( #12918 )

[Message] (MAVLink 2) Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm.

Field NameTypeValuesDescription
statusuint8_tMAV_ODID_ARM_STATUSStatus level indicating if arming is allowed.
errorchar[50]Text error message, should be empty if status is good to arm. Fill with nulls in unused portion.

OPEN_DRONE_ID_SYSTEM_UPDATE ( #12919 )

[Message] (MAVLink 2) Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID (0 for broadcast).
target_componentuint8_tComponent ID (0 for broadcast).
operator_latitudeint32_tdegE7Latitude of the operator. If unknown: 0 (both Lat/Lon).
operator_longitudeint32_tdegE7Longitude of the operator. If unknown: 0 (both Lat/Lon).
operator_altitude_geofloatmGeodetic altitude of the operator relative to WGS84. If unknown: -1000 m.
timestampuint32_ts32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.

HYGROMETER_SENSOR ( #12920 )

[Message] (MAVLink 2) Temperature and humidity from hygrometer.

Field NameTypeUnitsDescription
iduint8_tHygrometer ID
temperatureint16_tcdegCTemperature
humidityuint16_tc%Humidity

Minimal.xml

The minimal set of definitions required for any MAVLink system are included from minimal.xml. These are listed below.

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

MAVLink Type Enumerations

MAV_AUTOPILOT

[Enum] 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, https://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
20MAV_AUTOPILOT_REFLEXFusion Reflex - https://fusion.engineering

MAV_TYPE

[Enum] MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).

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_TAILSITTER_DUOROTORTwo-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR.
20MAV_TYPE_VTOL_TAILSITTER_QUADROTORQuad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR.
21MAV_TYPE_VTOL_TILTROTORTiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight.
22MAV_TYPE_VTOL_FIXEDROTORVTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases.
23MAV_TYPE_VTOL_TAILSITTERTailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate.
24MAV_TYPE_VTOL_TILTWINGTiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode.
25MAV_TYPE_VTOL_RESERVED5VTOL reserved 5
26MAV_TYPE_GIMBALGimbal
27MAV_TYPE_ADSBADSB system
28MAV_TYPE_PARAFOILSteerable, nonrigid airfoil
29MAV_TYPE_DODECAROTORDodecarotor
30MAV_TYPE_CAMERACamera
31MAV_TYPE_CHARGING_STATIONCharging station
32MAV_TYPE_FLARMFLARM collision avoidance system
33MAV_TYPE_SERVOServo
34MAV_TYPE_ODIDOpen Drone ID. See https://mavlink.io/en/services/opendroneid.html.
35MAV_TYPE_DECAROTORDecarotor
36MAV_TYPE_BATTERYBattery
37MAV_TYPE_PARACHUTEParachute
38MAV_TYPE_LOGLog
39MAV_TYPE_OSDOSD
40MAV_TYPE_IMUIMU
41MAV_TYPE_GPSGPS
42MAV_TYPE_WINCHWinch
43MAV_TYPE_GENERIC_MULTIROTORGeneric multirotor that does not fit into a specific type or whose type is unknown

MAV_MODE_FLAG

[Enum] 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

[Enum] 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_AUTOSixth bit: 00000100
2MAV_MODE_FLAG_DECODE_POSITION_TESTSeventh bit: 00000010
1MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODEEighth bit: 00000001

MAV_STATE

[Enum]

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

MAV_COMPONENT

[Enum] Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.

ValueField NameDescription
0MAV_COMP_ID_ALLTarget id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message.
1MAV_COMP_ID_AUTOPILOT1System flight controller component ("autopilot"). Only one autopilot is expected in a particular system.
25MAV_COMP_ID_USER1Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
26MAV_COMP_ID_USER2Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
27MAV_COMP_ID_USER3Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
28MAV_COMP_ID_USER4Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
29MAV_COMP_ID_USER5Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
30MAV_COMP_ID_USER6Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
31MAV_COMP_ID_USER7Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
32MAV_COMP_ID_USER8Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
33MAV_COMP_ID_USER9Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
34MAV_COMP_ID_USER10Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
35MAV_COMP_ID_USER11Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
36MAV_COMP_ID_USER12Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
37MAV_COMP_ID_USER13Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
38MAV_COMP_ID_USER14Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
39MAV_COMP_ID_USER15Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
40MAV_COMP_ID_USER16Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
41MAV_COMP_ID_USER17Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
42MAV_COMP_ID_USER18Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
43MAV_COMP_ID_USER19Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
44MAV_COMP_ID_USER20Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
45MAV_COMP_ID_USER21Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
46MAV_COMP_ID_USER22Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
47MAV_COMP_ID_USER23Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
48MAV_COMP_ID_USER24Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
49MAV_COMP_ID_USER25Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
50MAV_COMP_ID_USER26Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
51MAV_COMP_ID_USER27Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
52MAV_COMP_ID_USER28Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
53MAV_COMP_ID_USER29Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
54MAV_COMP_ID_USER30Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
55MAV_COMP_ID_USER31Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
56MAV_COMP_ID_USER32Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
57MAV_COMP_ID_USER33Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
58MAV_COMP_ID_USER34Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
59MAV_COMP_ID_USER35Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
60MAV_COMP_ID_USER36Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
61MAV_COMP_ID_USER37Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
62MAV_COMP_ID_USER38Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
63MAV_COMP_ID_USER39Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
64MAV_COMP_ID_USER40Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
65MAV_COMP_ID_USER41Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
66MAV_COMP_ID_USER42Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
67MAV_COMP_ID_USER43Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
68MAV_COMP_ID_TELEMETRY_RADIOTelemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
69MAV_COMP_ID_USER45Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
70MAV_COMP_ID_USER46Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
71MAV_COMP_ID_USER47Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
72MAV_COMP_ID_USER48Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
73MAV_COMP_ID_USER49Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
74MAV_COMP_ID_USER50Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
75MAV_COMP_ID_USER51Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
76MAV_COMP_ID_USER52Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
77MAV_COMP_ID_USER53Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
78MAV_COMP_ID_USER54Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
79MAV_COMP_ID_USER55Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
80MAV_COMP_ID_USER56Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
81MAV_COMP_ID_USER57Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
82MAV_COMP_ID_USER58Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
83MAV_COMP_ID_USER59Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
84MAV_COMP_ID_USER60Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
85MAV_COMP_ID_USER61Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
86MAV_COMP_ID_USER62Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
87MAV_COMP_ID_USER63Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
88MAV_COMP_ID_USER64Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
89MAV_COMP_ID_USER65Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
90MAV_COMP_ID_USER66Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
91MAV_COMP_ID_USER67Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
92MAV_COMP_ID_USER68Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
93MAV_COMP_ID_USER69Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
94MAV_COMP_ID_USER70Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
95MAV_COMP_ID_USER71Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
96MAV_COMP_ID_USER72Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
97MAV_COMP_ID_USER73Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
98MAV_COMP_ID_USER74Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
99MAV_COMP_ID_USER75Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
100MAV_COMP_ID_CAMERACamera #1.
101MAV_COMP_ID_CAMERA2Camera #2.
102MAV_COMP_ID_CAMERA3Camera #3.
103MAV_COMP_ID_CAMERA4Camera #4.
104MAV_COMP_ID_CAMERA5Camera #5.
105MAV_COMP_ID_CAMERA6Camera #6.
140MAV_COMP_ID_SERVO1Servo #1.
141MAV_COMP_ID_SERVO2Servo #2.
142MAV_COMP_ID_SERVO3Servo #3.
143MAV_COMP_ID_SERVO4Servo #4.
144MAV_COMP_ID_SERVO5Servo #5.
145MAV_COMP_ID_SERVO6Servo #6.
146MAV_COMP_ID_SERVO7Servo #7.
147MAV_COMP_ID_SERVO8Servo #8.
148MAV_COMP_ID_SERVO9Servo #9.
149MAV_COMP_ID_SERVO10Servo #10.
150MAV_COMP_ID_SERVO11Servo #11.
151MAV_COMP_ID_SERVO12Servo #12.
152MAV_COMP_ID_SERVO13Servo #13.
153MAV_COMP_ID_SERVO14Servo #14.
154MAV_COMP_ID_GIMBALGimbal #1.
155MAV_COMP_ID_LOGLogging component.
156MAV_COMP_ID_ADSBAutomatic Dependent Surveillance-Broadcast (ADS-B) component.
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 microservice.
159MAV_COMP_ID_QX1_GIMBAL

DEPRECATED: Replaced by MAV_COMP_ID_GIMBAL (2018-11). All gimbals should use MAV_COMP_ID_GIMBAL.

Gimbal ID for QX1.
160MAV_COMP_ID_FLARMFLARM collision alert component.
161MAV_COMP_ID_PARACHUTEParachute component.
169MAV_COMP_ID_WINCHWinch component.
171MAV_COMP_ID_GIMBAL2Gimbal #2.
172MAV_COMP_ID_GIMBAL3Gimbal #3.
173MAV_COMP_ID_GIMBAL4Gimbal #4
174MAV_COMP_ID_GIMBAL5Gimbal #5.
175MAV_COMP_ID_GIMBAL6Gimbal #6.
180MAV_COMP_ID_BATTERYBattery #1.
181MAV_COMP_ID_BATTERY2Battery #2.
189MAV_COMP_ID_MAVCANCAN over MAVLink client.
190MAV_COMP_ID_MISSIONPLANNERComponent that can generate/supply a mission flight plan (e.g. GCS or developer API).
191MAV_COMP_ID_ONBOARD_COMPUTERComponent that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
192MAV_COMP_ID_ONBOARD_COMPUTER2Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
193MAV_COMP_ID_ONBOARD_COMPUTER3Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
194MAV_COMP_ID_ONBOARD_COMPUTER4Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
195MAV_COMP_ID_PATHPLANNERComponent that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
196MAV_COMP_ID_OBSTACLE_AVOIDANCEComponent that plans a collision free path between two points.
197MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRYComponent that provides position estimates using VIO techniques.
198MAV_COMP_ID_PAIRING_MANAGERComponent that manages pairing of vehicle and GCS.
200MAV_COMP_ID_IMUInertial Measurement Unit (IMU) #1.
201MAV_COMP_ID_IMU_2Inertial Measurement Unit (IMU) #2.
202MAV_COMP_ID_IMU_3Inertial Measurement Unit (IMU) #3.
220MAV_COMP_ID_GPSGPS #1.
221MAV_COMP_ID_GPS2GPS #2.
236MAV_COMP_ID_ODID_TXRX_1Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
237MAV_COMP_ID_ODID_TXRX_2Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
238MAV_COMP_ID_ODID_TXRX_3Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
240MAV_COMP_ID_UDP_BRIDGEComponent to bridge MAVLink to UDP (i.e. from a UART).
241MAV_COMP_ID_UART_BRIDGEComponent to bridge to UART (i.e. from UDP).
242MAV_COMP_ID_TUNNEL_NODEComponent handling TUNNEL messages (e.g. vendor specific GUI of a component).
250MAV_COMP_ID_SYSTEM_CONTROL

DEPRECATED: Replaced by MAV_COMP_ID_ALL (2018-11). System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id.

Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.).

MAVLink Commands (MAV_CMD)

MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.

MAVLink Messages

HEARTBEAT ( #0 )

[Message] The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html

Field NameTypeValuesDescription
typeuint8_tMAV_TYPEVehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
autopilotuint8_tMAV_AUTOPILOTAutopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
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

PROTOCOL_VERSION ( #300 )

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

[Message] (MAVLink 2) Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly.

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.

results matching ""

    No results matching ""