Skip to content
Permalink
master
Switch branches/tags

Name already in use

A tag already exists with the provided branch name. Many Git commands accept both tag and branch names, so creating this branch may cause unexpected behavior. Are you sure you want to create this branch?
Go to file
145 contributors

Users who have contributed to this file

@hamishwillee @julianoes @LorenzMeier @tridge @dogmaphobic @amilcarlucas @olliw42 @peterbarker @TSC21 @thomasgubler @MaEtUgR @dagar
<?xml version="1.0"?>
<mavlink>
<include>standard.xml</include>
<version>3</version>
<dialect>0</dialect>
<enums>
<enum name="FIRMWARE_VERSION_TYPE">
<description>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.</description>
<entry value="0" name="FIRMWARE_VERSION_TYPE_DEV">
<description>development release</description>
</entry>
<entry value="64" name="FIRMWARE_VERSION_TYPE_ALPHA">
<description>alpha release</description>
</entry>
<entry value="128" name="FIRMWARE_VERSION_TYPE_BETA">
<description>beta release</description>
</entry>
<entry value="192" name="FIRMWARE_VERSION_TYPE_RC">
<description>release candidate</description>
</entry>
<entry value="255" name="FIRMWARE_VERSION_TYPE_OFFICIAL">
<description>official stable release</description>
</entry>
</enum>
<enum name="HL_FAILURE_FLAG" bitmask="true">
<description>Flags to report failure cases over the high latency telemtry.</description>
<entry value="1" name="HL_FAILURE_FLAG_GPS">
<description>GPS failure.</description>
</entry>
<entry value="2" name="HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE">
<description>Differential pressure sensor failure.</description>
</entry>
<entry value="4" name="HL_FAILURE_FLAG_ABSOLUTE_PRESSURE">
<description>Absolute pressure sensor failure.</description>
</entry>
<entry value="8" name="HL_FAILURE_FLAG_3D_ACCEL">
<description>Accelerometer sensor failure.</description>
</entry>
<entry value="16" name="HL_FAILURE_FLAG_3D_GYRO">
<description>Gyroscope sensor failure.</description>
</entry>
<entry value="32" name="HL_FAILURE_FLAG_3D_MAG">
<description>Magnetometer sensor failure.</description>
</entry>
<entry value="64" name="HL_FAILURE_FLAG_TERRAIN">
<description>Terrain subsystem failure.</description>
</entry>
<entry value="128" name="HL_FAILURE_FLAG_BATTERY">
<description>Battery failure/critical low battery.</description>
</entry>
<entry value="256" name="HL_FAILURE_FLAG_RC_RECEIVER">
<description>RC receiver failure/no rc connection.</description>
</entry>
<entry value="512" name="HL_FAILURE_FLAG_OFFBOARD_LINK">
<description>Offboard link failure.</description>
</entry>
<entry value="1024" name="HL_FAILURE_FLAG_ENGINE">
<description>Engine failure.</description>
</entry>
<entry value="2048" name="HL_FAILURE_FLAG_GEOFENCE">
<description>Geofence violation.</description>
</entry>
<entry value="4096" name="HL_FAILURE_FLAG_ESTIMATOR">
<description>Estimator failure, for example measurement rejection or large variances.</description>
</entry>
<entry value="8192" name="HL_FAILURE_FLAG_MISSION">
<description>Mission failure.</description>
</entry>
</enum>
<enum name="MAV_GOTO">
<description>Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution.</description>
<entry value="0" name="MAV_GOTO_DO_HOLD">
<description>Hold at the current position.</description>
</entry>
<entry value="1" name="MAV_GOTO_DO_CONTINUE">
<description>Continue with the next item in mission execution.</description>
</entry>
<entry value="2" name="MAV_GOTO_HOLD_AT_CURRENT_POSITION">
<description>Hold at the current position of the system</description>
</entry>
<entry value="3" name="MAV_GOTO_HOLD_AT_SPECIFIED_POSITION">
<description>Hold at the position specified in the parameters of the DO_HOLD action</description>
</entry>
</enum>
<enum name="MAV_MODE">
<description>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.</description>
<entry value="0" name="MAV_MODE_PREFLIGHT">
<description>System is not ready to fly, booting, calibrating, etc. No flag is set.</description>
</entry>
<entry value="80" name="MAV_MODE_STABILIZE_DISARMED">
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entry value="208" name="MAV_MODE_STABILIZE_ARMED">
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entry value="64" name="MAV_MODE_MANUAL_DISARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entry value="192" name="MAV_MODE_MANUAL_ARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entry value="88" name="MAV_MODE_GUIDED_DISARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entry value="216" name="MAV_MODE_GUIDED_ARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entry value="92" name="MAV_MODE_AUTO_DISARMED">
<description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)</description>
</entry>
<entry value="220" name="MAV_MODE_AUTO_ARMED">
<description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)</description>
</entry>
<entry value="66" name="MAV_MODE_TEST_DISARMED">
<description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description>
</entry>
<entry value="194" name="MAV_MODE_TEST_ARMED">
<description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description>
</entry>
</enum>
<enum name="MAV_SYS_STATUS_SENSOR" bitmask="true">
<description>These encode the sensors whose status is sent as part of the SYS_STATUS message.</description>
<entry value="1" name="MAV_SYS_STATUS_SENSOR_3D_GYRO">
<description>0x01 3D gyro</description>
</entry>
<entry value="2" name="MAV_SYS_STATUS_SENSOR_3D_ACCEL">
<description>0x02 3D accelerometer</description>
</entry>
<entry value="4" name="MAV_SYS_STATUS_SENSOR_3D_MAG">
<description>0x04 3D magnetometer</description>
</entry>
<entry value="8" name="MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE">
<description>0x08 absolute pressure</description>
</entry>
<entry value="16" name="MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE">
<description>0x10 differential pressure</description>
</entry>
<entry value="32" name="MAV_SYS_STATUS_SENSOR_GPS">
<description>0x20 GPS</description>
</entry>
<entry value="64" name="MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW">
<description>0x40 optical flow</description>
</entry>
<entry value="128" name="MAV_SYS_STATUS_SENSOR_VISION_POSITION">
<description>0x80 computer vision position</description>
</entry>
<entry value="256" name="MAV_SYS_STATUS_SENSOR_LASER_POSITION">
<description>0x100 laser based position</description>
</entry>
<entry value="512" name="MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH">
<description>0x200 external ground truth (Vicon or Leica)</description>
</entry>
<entry value="1024" name="MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL">
<description>0x400 3D angular rate control</description>
</entry>
<entry value="2048" name="MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION">
<description>0x800 attitude stabilization</description>
</entry>
<entry value="4096" name="MAV_SYS_STATUS_SENSOR_YAW_POSITION">
<description>0x1000 yaw position</description>
</entry>
<entry value="8192" name="MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL">
<description>0x2000 z/altitude control</description>
</entry>
<entry value="16384" name="MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL">
<description>0x4000 x/y position control</description>
</entry>
<entry value="32768" name="MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS">
<description>0x8000 motor outputs / control</description>
</entry>
<entry value="65536" name="MAV_SYS_STATUS_SENSOR_RC_RECEIVER">
<description>0x10000 rc receiver</description>
</entry>
<entry value="131072" name="MAV_SYS_STATUS_SENSOR_3D_GYRO2">
<description>0x20000 2nd 3D gyro</description>
</entry>
<entry value="262144" name="MAV_SYS_STATUS_SENSOR_3D_ACCEL2">
<description>0x40000 2nd 3D accelerometer</description>
</entry>
<entry value="524288" name="MAV_SYS_STATUS_SENSOR_3D_MAG2">
<description>0x80000 2nd 3D magnetometer</description>
</entry>
<entry value="1048576" name="MAV_SYS_STATUS_GEOFENCE">
<description>0x100000 geofence</description>
</entry>
<entry value="2097152" name="MAV_SYS_STATUS_AHRS">
<description>0x200000 AHRS subsystem health</description>
</entry>
<entry value="4194304" name="MAV_SYS_STATUS_TERRAIN">
<description>0x400000 Terrain subsystem health</description>
</entry>
<entry value="8388608" name="MAV_SYS_STATUS_REVERSE_MOTOR">
<description>0x800000 Motors are reversed</description>
</entry>
<entry value="16777216" name="MAV_SYS_STATUS_LOGGING">
<description>0x1000000 Logging</description>
</entry>
<entry value="33554432" name="MAV_SYS_STATUS_SENSOR_BATTERY">
<description>0x2000000 Battery</description>
</entry>
<entry value="67108864" name="MAV_SYS_STATUS_SENSOR_PROXIMITY">
<description>0x4000000 Proximity</description>
</entry>
<entry value="134217728" name="MAV_SYS_STATUS_SENSOR_SATCOM">
<description>0x8000000 Satellite Communication </description>
</entry>
<entry value="268435456" name="MAV_SYS_STATUS_PREARM_CHECK">
<description>0x10000000 pre-arm check status. Always healthy when armed</description>
</entry>
<entry value="536870912" name="MAV_SYS_STATUS_OBSTACLE_AVOIDANCE">
<description>0x20000000 Avoidance/collision prevention</description>
</entry>
<entry value="1073741824" name="MAV_SYS_STATUS_SENSOR_PROPULSION">
<description>0x40000000 propulsion (actuator, esc, motor or propellor)</description>
</entry>
<entry value="2147483648" name="MAV_SYS_STATUS_EXTENSION_USED">
<description>0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)</description>
</entry>
</enum>
<enum name="MAV_SYS_STATUS_SENSOR_EXTENDED" bitmask="true">
<description>These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields.</description>
<entry value="1" name="MAV_SYS_STATUS_RECOVERY_SYSTEM">
<description>0x01 Recovery system (parachute, balloon, retracts etc)</description>
</entry>
</enum>
<enum name="MAV_FRAME">
<description>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).
</description>
<entry value="0" name="MAV_FRAME_GLOBAL">
<description>Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).</description>
</entry>
<entry value="1" name="MAV_FRAME_LOCAL_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.</description>
</entry>
<entry value="2" name="MAV_FRAME_MISSION">
<description>NOT a coordinate frame, indicates a mission command.</description>
</entry>
<entry value="3" name="MAV_FRAME_GLOBAL_RELATIVE_ALT">
<description>
Global (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.
</description>
</entry>
<entry value="4" name="MAV_FRAME_LOCAL_ENU">
<description>ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.</description>
</entry>
<entry value="5" name="MAV_FRAME_GLOBAL_INT">
<description>Global (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).</description>
</entry>
<entry value="6" name="MAV_FRAME_GLOBAL_RELATIVE_ALT_INT">
<description>
Global (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.
</description>
</entry>
<entry value="7" name="MAV_FRAME_LOCAL_OFFSET_NED">
<description>NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.</description>
</entry>
<entry value="8" name="MAV_FRAME_BODY_NED">
<deprecated since="2019-08" replaced_by="MAV_FRAME_BODY_FRD"/>
<description>Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.</description>
</entry>
<entry value="9" name="MAV_FRAME_BODY_OFFSET_NED">
<deprecated since="2019-08" replaced_by="MAV_FRAME_BODY_FRD"/>
<description>This is the same as MAV_FRAME_BODY_FRD.</description>
</entry>
<entry value="10" name="MAV_FRAME_GLOBAL_TERRAIN_ALT">
<description>Global (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.</description>
</entry>
<entry value="11" name="MAV_FRAME_GLOBAL_TERRAIN_ALT_INT">
<description>Global (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.</description>
</entry>
<entry value="12" name="MAV_FRAME_BODY_FRD">
<description>FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.</description>
</entry>
<entry value="13" name="MAV_FRAME_RESERVED_13">
<deprecated since="2019-04" replaced_by=""/>
<description>MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).</description>
</entry>
<entry value="14" name="MAV_FRAME_RESERVED_14">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FRD"/>
<description>MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).</description>
</entry>
<entry value="15" name="MAV_FRAME_RESERVED_15">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FLU"/>
<description>MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).</description>
</entry>
<entry value="16" name="MAV_FRAME_RESERVED_16">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FRD"/>
<description>MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).</description>
</entry>
<entry value="17" name="MAV_FRAME_RESERVED_17">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FLU"/>
<description>MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up).</description>
</entry>
<entry value="18" name="MAV_FRAME_RESERVED_18">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FRD"/>
<description>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).</description>
</entry>
<entry value="19" name="MAV_FRAME_RESERVED_19">
<deprecated since="2019-04" replaced_by="MAV_FRAME_LOCAL_FLU"/>
<description>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).</description>
</entry>
<entry value="20" name="MAV_FRAME_LOCAL_FRD">
<description>FRD 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.</description>
</entry>
<entry value="21" name="MAV_FRAME_LOCAL_FLU">
<description>FLU 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.</description>
</entry>
</enum>
<enum name="MAVLINK_DATA_STREAM_TYPE">
<entry value="0" name="MAVLINK_DATA_STREAM_IMG_JPEG">
<description/>
</entry>
<entry value="1" name="MAVLINK_DATA_STREAM_IMG_BMP">
<description/>
</entry>
<entry value="2" name="MAVLINK_DATA_STREAM_IMG_RAW8U">
<description/>
</entry>
<entry value="3" name="MAVLINK_DATA_STREAM_IMG_RAW32U">
<description/>
</entry>
<entry value="4" name="MAVLINK_DATA_STREAM_IMG_PGM">
<description/>
</entry>
<entry value="5" name="MAVLINK_DATA_STREAM_IMG_PNG">
<description/>
</entry>
</enum>
<!-- fenced mode enums -->
<enum name="FENCE_ACTION">
<description>Actions following geofence breach.</description>
<entry value="0" name="FENCE_ACTION_NONE">
<description>Disable fenced mode. If used in a plan this would mean the next fence is disabled.</description>
</entry>
<entry value="1" name="FENCE_ACTION_GUIDED">
<description>Fly 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.</description>
</entry>
<entry value="2" name="FENCE_ACTION_REPORT">
<description>Report fence breach, but don't take action</description>
</entry>
<entry value="3" name="FENCE_ACTION_GUIDED_THR_PASS">
<description>Fly 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.</description>
</entry>
<entry value="4" name="FENCE_ACTION_RTL">
<description>Return/RTL mode.</description>
</entry>
<entry value="5" name="FENCE_ACTION_HOLD">
<description>Hold at current location.</description>
</entry>
<entry value="6" name="FENCE_ACTION_TERMINATE">
<description>Termination failsafe. Motors are shut down (some flight stacks may trigger other failsafe actions).</description>
</entry>
<entry value="7" name="FENCE_ACTION_LAND">
<description>Land at current location.</description>
</entry>
</enum>
<enum name="FENCE_BREACH">
<entry value="0" name="FENCE_BREACH_NONE">
<description>No last fence breach</description>
</entry>
<entry value="1" name="FENCE_BREACH_MINALT">
<description>Breached minimum altitude</description>
</entry>
<entry value="2" name="FENCE_BREACH_MAXALT">
<description>Breached maximum altitude</description>
</entry>
<entry value="3" name="FENCE_BREACH_BOUNDARY">
<description>Breached fence boundary</description>
</entry>
</enum>
<enum name="FENCE_MITIGATE">
<!-- This enum is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Actions being taken to mitigate/prevent fence breach</description>
<entry value="0" name="FENCE_MITIGATE_UNKNOWN">
<description>Unknown</description>
</entry>
<entry value="1" name="FENCE_MITIGATE_NONE">
<description>No actions being taken</description>
</entry>
<entry value="2" name="FENCE_MITIGATE_VEL_LIMIT">
<description>Velocity limiting active to prevent breach</description>
</entry>
</enum>
<!-- Camera Mount mode Enumeration -->
<enum name="MAV_MOUNT_MODE">
<deprecated since="2020-01" replaced_by="GIMBAL_MANAGER_FLAGS"/>
<description>Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.</description>
<entry value="0" name="MAV_MOUNT_MODE_RETRACT">
<description>Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization</description>
</entry>
<entry value="1" name="MAV_MOUNT_MODE_NEUTRAL">
<description>Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.</description>
</entry>
<entry value="2" name="MAV_MOUNT_MODE_MAVLINK_TARGETING">
<description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description>
</entry>
<entry value="3" name="MAV_MOUNT_MODE_RC_TARGETING">
<description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description>
</entry>
<entry value="4" name="MAV_MOUNT_MODE_GPS_POINT">
<description>Load neutral position and start to point to Lat,Lon,Alt</description>
</entry>
<entry value="5" name="MAV_MOUNT_MODE_SYSID_TARGET">
<description>Gimbal tracks system with specified system ID</description>
</entry>
<entry value="6" name="MAV_MOUNT_MODE_HOME_LOCATION">
<description>Gimbal tracks home position</description>
</entry>
</enum>
<enum name="GIMBAL_DEVICE_CAP_FLAGS" bitmask="true">
<description>Gimbal device (low level) capability flags (bitmap).</description>
<entry value="1" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT">
<description>Gimbal device supports a retracted position.</description>
</entry>
<entry value="2" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL">
<description>Gimbal device supports a horizontal, forward looking position, stabilized.</description>
</entry>
<entry value="4" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS">
<description>Gimbal device supports rotating around roll axis.</description>
</entry>
<entry value="8" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW">
<description>Gimbal device supports to follow a roll angle relative to the vehicle.</description>
</entry>
<entry value="16" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK">
<description>Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized).</description>
</entry>
<entry value="32" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS">
<description>Gimbal device supports rotating around pitch axis.</description>
</entry>
<entry value="64" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW">
<description>Gimbal device supports to follow a pitch angle relative to the vehicle.</description>
</entry>
<entry value="128" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK">
<description>Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized).</description>
</entry>
<entry value="256" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS">
<description>Gimbal device supports rotating around yaw axis.</description>
</entry>
<entry value="512" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW">
<description>Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).</description>
</entry>
<entry value="1024" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK">
<description>Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).</description>
</entry>
<entry value="2048" name="GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW">
<description>Gimbal device supports yawing/panning infinetely (e.g. using slip disk).</description>
</entry>
<entry value="4096" name="GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME">
<description>Gimbal 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.</description>
</entry>
<entry value="8192" name="GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS">
<description>Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation.</description>
</entry>
</enum>
<enum name="GIMBAL_MANAGER_CAP_FLAGS" bitmask="true">
<description>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.</description>
<entry value="1" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT.</description>
</entry>
<entry value="2" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL.</description>
</entry>
<entry value="4" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS.</description>
</entry>
<entry value="8" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW.</description>
</entry>
<entry value="16" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK.</description>
</entry>
<entry value="32" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS.</description>
</entry>
<entry value="64" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW.</description>
</entry>
<entry value="128" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK.</description>
</entry>
<entry value="256" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS.</description>
</entry>
<entry value="512" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW.</description>
</entry>
<entry value="1024" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK.</description>
</entry>
<entry value="2048" name="GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW.</description>
</entry>
<entry value="4096" name="GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME.</description>
</entry>
<entry value="8192" name="GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS">
<description>Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS.</description>
</entry>
<entry value="65536" name="GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL">
<description>Gimbal manager supports to point to a local position.</description>
</entry>
<entry value="131072" name="GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL">
<description>Gimbal manager supports to point to a global latitude, longitude, altitude position.</description>
</entry>
</enum>
<enum name="GIMBAL_DEVICE_FLAGS" bitmask="true">
<description>Flags for gimbal device (lower level) operation.</description>
<entry value="1" name="GIMBAL_DEVICE_FLAGS_RETRACT">
<description>Set to retracted safe position (no stabilization), takes presedence over all other flags.</description>
</entry>
<entry value="2" name="GIMBAL_DEVICE_FLAGS_NEUTRAL">
<description>Set 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.</description>
</entry>
<entry value="4" name="GIMBAL_DEVICE_FLAGS_ROLL_LOCK">
<description>Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.</description>
</entry>
<entry value="8" name="GIMBAL_DEVICE_FLAGS_PITCH_LOCK">
<description>Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal.</description>
</entry>
<entry value="16" name="GIMBAL_DEVICE_FLAGS_YAW_LOCK">
<description>Lock 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).</description>
</entry>
<entry value="32" name="GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME">
<description>Yaw 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).</description>
</entry>
<entry value="64" name="GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME">
<description>Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North).</description>
</entry>
<entry value="128" name="GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME">
<description>Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored).</description>
</entry>
<entry value="256" name="GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE">
<description>The 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.</description>
</entry>
<entry value="512" name="GIMBAL_DEVICE_FLAGS_RC_MIXED">
<description>The 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.</description>
</entry>
</enum>
<enum name="GIMBAL_MANAGER_FLAGS" bitmask="true">
<description>Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS.</description>
<entry value="1" name="GIMBAL_MANAGER_FLAGS_RETRACT">
<description>Based on GIMBAL_DEVICE_FLAGS_RETRACT.</description>
</entry>
<entry value="2" name="GIMBAL_MANAGER_FLAGS_NEUTRAL">
<description>Based on GIMBAL_DEVICE_FLAGS_NEUTRAL.</description>
</entry>
<entry value="4" name="GIMBAL_MANAGER_FLAGS_ROLL_LOCK">
<description>Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK.</description>
</entry>
<entry value="8" name="GIMBAL_MANAGER_FLAGS_PITCH_LOCK">
<description>Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK.</description>
</entry>
<entry value="16" name="GIMBAL_MANAGER_FLAGS_YAW_LOCK">
<description>Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK.</description>
</entry>
<entry value="32" name="GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME">
<description>Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME.</description>
</entry>
<entry value="64" name="GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME">
<description>Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME.</description>
</entry>
<entry value="128" name="GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME">
<description>Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME.</description>
</entry>
<entry value="256" name="GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE">
<description>Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE.</description>
</entry>
<entry value="512" name="GIMBAL_MANAGER_FLAGS_RC_MIXED">
<description>Based on GIMBAL_DEVICE_FLAGS_RC_MIXED.</description>
</entry>
</enum>
<enum name="GIMBAL_DEVICE_ERROR_FLAGS" bitmask="true">
<description>Gimbal device (low level) error flags (bitmap, 0 means no error)</description>
<entry value="1" name="GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT">
<description>Gimbal device is limited by hardware roll limit.</description>
</entry>
<entry value="2" name="GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT">
<description>Gimbal device is limited by hardware pitch limit.</description>
</entry>
<entry value="4" name="GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT">
<description>Gimbal device is limited by hardware yaw limit.</description>
</entry>
<entry value="8" name="GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR">
<description>There is an error with the gimbal encoders.</description>
</entry>
<entry value="16" name="GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR">
<description>There is an error with the gimbal power source.</description>
</entry>
<entry value="32" name="GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR">
<description>There is an error with the gimbal motors.</description>
</entry>
<entry value="64" name="GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR">
<description>There is an error with the gimbal's software.</description>
</entry>
<entry value="128" name="GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR">
<description>There is an error with the gimbal's communication.</description>
</entry>
<entry value="256" name="GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING">
<description>Gimbal device is currently calibrating.</description>
</entry>
<entry value="512" name="GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER">
<description>Gimbal device is not assigned to a gimbal manager.</description>
</entry>
</enum>
<!-- gripper action enum -->
<enum name="GRIPPER_ACTIONS">
<description>Gripper actions.</description>
<entry value="0" name="GRIPPER_ACTION_RELEASE">
<description>Gripper release cargo.</description>
</entry>
<entry value="1" name="GRIPPER_ACTION_GRAB">
<description>Gripper grab onto cargo.</description>
</entry>
</enum>
<!-- winch action enum -->
<enum name="WINCH_ACTIONS">
<description>Winch actions.</description>
<entry value="0" name="WINCH_RELAXED">
<description>Allow motor to freewheel.</description>
</entry>
<entry value="1" name="WINCH_RELATIVE_LENGTH_CONTROL">
<description>Wind or unwind specified length of line, optionally using specified rate.</description>
</entry>
<entry value="2" name="WINCH_RATE_CONTROL">
<description>Wind or unwind line at specified rate.</description>
</entry>
<entry value="3" name="WINCH_LOCK">
<description>Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored.</description>
</entry>
<entry value="4" name="WINCH_DELIVER">
<description>Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored.</description>
</entry>
<entry value="5" name="WINCH_HOLD">
<description>Engage motor and hold current position. Only action and instance command parameters are used, others are ignored.</description>
</entry>
<entry value="6" name="WINCH_RETRACT">
<description>Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored.</description>
</entry>
<entry value="7" name="WINCH_LOAD_LINE">
<description>Load 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.</description>
</entry>
<entry value="8" name="WINCH_ABANDON_LINE">
<description>Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored.</description>
</entry>
<entry value="9" name="WINCH_LOAD_PAYLOAD">
<description>Spools 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</description>
</entry>
</enum>
<!-- UAVCAN node health enumeration -->
<enum name="UAVCAN_NODE_HEALTH">
<description>Generalized UAVCAN node health</description>
<entry value="0" name="UAVCAN_NODE_HEALTH_OK">
<description>The node is functioning properly.</description>
</entry>
<entry value="1" name="UAVCAN_NODE_HEALTH_WARNING">
<description>A critical parameter went out of range or the node has encountered a minor failure.</description>
</entry>
<entry value="2" name="UAVCAN_NODE_HEALTH_ERROR">
<description>The node has encountered a major failure.</description>
</entry>
<entry value="3" name="UAVCAN_NODE_HEALTH_CRITICAL">
<description>The node has suffered a fatal malfunction.</description>
</entry>
</enum>
<!-- UAVCAN node mode enumeration -->
<enum name="UAVCAN_NODE_MODE">
<description>Generalized UAVCAN node mode</description>
<entry value="0" name="UAVCAN_NODE_MODE_OPERATIONAL">
<description>The node is performing its primary functions.</description>
</entry>
<entry value="1" name="UAVCAN_NODE_MODE_INITIALIZATION">
<description>The node is initializing; this mode is entered immediately after startup.</description>
</entry>
<entry value="2" name="UAVCAN_NODE_MODE_MAINTENANCE">
<description>The node is under maintenance.</description>
</entry>
<entry value="3" name="UAVCAN_NODE_MODE_SOFTWARE_UPDATE">
<description>The node is in the process of updating its software.</description>
</entry>
<entry value="7" name="UAVCAN_NODE_MODE_OFFLINE">
<description>The node is no longer available online.</description>
</entry>
</enum>
<enum name="ESC_CONNECTION_TYPE">
<!-- This enum is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Indicates the ESC connection type.</description>
<entry value="0" name="ESC_CONNECTION_TYPE_PPM">
<description>Traditional PPM ESC.</description>
</entry>
<entry value="1" name="ESC_CONNECTION_TYPE_SERIAL">
<description>Serial Bus connected ESC.</description>
</entry>
<entry value="2" name="ESC_CONNECTION_TYPE_ONESHOT">
<description>One Shot PPM ESC.</description>
</entry>
<entry value="3" name="ESC_CONNECTION_TYPE_I2C">
<description>I2C ESC.</description>
</entry>
<entry value="4" name="ESC_CONNECTION_TYPE_CAN">
<description>CAN-Bus ESC.</description>
</entry>
<entry value="5" name="ESC_CONNECTION_TYPE_DSHOT">
<description>DShot ESC.</description>
</entry>
</enum>
<enum name="ESC_FAILURE_FLAGS" bitmask="true">
<!-- This enum is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Flags to report ESC failures.</description>
<entry value="0" name="ESC_FAILURE_NONE">
<description>No ESC failure.</description>
</entry>
<entry value="1" name="ESC_FAILURE_OVER_CURRENT">
<description>Over current failure.</description>
</entry>
<entry value="2" name="ESC_FAILURE_OVER_VOLTAGE">
<description>Over voltage failure.</description>
</entry>
<entry value="4" name="ESC_FAILURE_OVER_TEMPERATURE">
<description>Over temperature failure.</description>
</entry>
<entry value="8" name="ESC_FAILURE_OVER_RPM">
<description>Over RPM failure.</description>
</entry>
<entry value="16" name="ESC_FAILURE_INCONSISTENT_CMD">
<description>Inconsistent command failure i.e. out of bounds.</description>
</entry>
<entry value="32" name="ESC_FAILURE_MOTOR_STUCK">
<description>Motor stuck failure.</description>
</entry>
<entry value="64" name="ESC_FAILURE_GENERIC">
<description>Generic ESC failure.</description>
</entry>
</enum>
<enum name="STORAGE_STATUS">
<description>Flags to indicate the status of camera storage.</description>
<entry value="0" name="STORAGE_STATUS_EMPTY">
<description>Storage is missing (no microSD card loaded for example.)</description>
</entry>
<entry value="1" name="STORAGE_STATUS_UNFORMATTED">
<description>Storage present but unformatted.</description>
</entry>
<entry value="2" name="STORAGE_STATUS_READY">
<description>Storage present and ready.</description>
</entry>
<entry value="3" name="STORAGE_STATUS_NOT_SUPPORTED">
<description>Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored.</description>
</entry>
</enum>
<enum name="STORAGE_TYPE">
<description>Flags to indicate the type of storage.</description>
<entry value="0" name="STORAGE_TYPE_UNKNOWN">
<description>Storage type is not known.</description>
</entry>
<entry value="1" name="STORAGE_TYPE_USB_STICK">
<description>Storage type is USB device.</description>
</entry>
<entry value="2" name="STORAGE_TYPE_SD">
<description>Storage type is SD card.</description>
</entry>
<entry value="3" name="STORAGE_TYPE_MICROSD">
<description>Storage type is microSD card.</description>
</entry>
<entry value="4" name="STORAGE_TYPE_CF">
<description>Storage type is CFast.</description>
</entry>
<entry value="5" name="STORAGE_TYPE_CFE">
<description>Storage type is CFexpress.</description>
</entry>
<entry value="6" name="STORAGE_TYPE_XQD">
<description>Storage type is XQD.</description>
</entry>
<entry value="7" name="STORAGE_TYPE_HD">
<description>Storage type is HD mass storage type.</description>
</entry>
<entry value="254" name="STORAGE_TYPE_OTHER">
<description>Storage type is other, not listed type.</description>
</entry>
</enum>
<enum name="STORAGE_USAGE_FLAG">
<description>Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE).</description>
<entry value="1" name="STORAGE_USAGE_FLAG_SET">
<description>Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported).</description>
</entry>
<entry value="2" name="STORAGE_USAGE_FLAG_PHOTO">
<description>Storage for saving photos.</description>
</entry>
<entry value="4" name="STORAGE_USAGE_FLAG_VIDEO">
<description>Storage for saving videos.</description>
</entry>
<entry value="8" name="STORAGE_USAGE_FLAG_LOGS">
<description>Storage for saving logs.</description>
</entry>
</enum>
<enum name="ORBIT_YAW_BEHAVIOUR">
<description>Yaw behaviour during orbit flight.</description>
<entry value="0" name="ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER">
<description>Vehicle front points to the center (default).</description>
</entry>
<entry value="1" name="ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING">
<description>Vehicle front holds heading when message received.</description>
</entry>
<entry value="2" name="ORBIT_YAW_BEHAVIOUR_UNCONTROLLED">
<description>Yaw uncontrolled.</description>
</entry>
<entry value="3" name="ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE">
<description>Vehicle front follows flight path (tangential to circle).</description>
</entry>
<entry value="4" name="ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED">
<description>Yaw controlled by RC input.</description>
</entry>
</enum>
<enum name="WIFI_CONFIG_AP_RESPONSE">
<description>Possible responses from a WIFI_CONFIG_AP message.</description>
<entry value="0" name="WIFI_CONFIG_AP_RESPONSE_UNDEFINED">
<description>Undefined response. Likely an indicative of a system that doesn't support this request.</description>
</entry>
<entry value="1" name="WIFI_CONFIG_AP_RESPONSE_ACCEPTED">
<description>Changes accepted.</description>
</entry>
<entry value="2" name="WIFI_CONFIG_AP_RESPONSE_REJECTED">
<description>Changes rejected.</description>
</entry>
<entry value="3" name="WIFI_CONFIG_AP_RESPONSE_MODE_ERROR">
<description>Invalid Mode.</description>
</entry>
<entry value="4" name="WIFI_CONFIG_AP_RESPONSE_SSID_ERROR">
<description>Invalid SSID.</description>
</entry>
<entry value="5" name="WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR">
<description>Invalid Password.</description>
</entry>
</enum>
<enum name="CELLULAR_CONFIG_RESPONSE">
<description>Possible responses from a CELLULAR_CONFIG message.</description>
<entry value="0" name="CELLULAR_CONFIG_RESPONSE_ACCEPTED">
<description>Changes accepted.</description>
</entry>
<entry value="1" name="CELLULAR_CONFIG_RESPONSE_APN_ERROR">
<description>Invalid APN.</description>
</entry>
<entry value="2" name="CELLULAR_CONFIG_RESPONSE_PIN_ERROR">
<description>Invalid PIN.</description>
</entry>
<entry value="3" name="CELLULAR_CONFIG_RESPONSE_REJECTED">
<description>Changes rejected.</description>
</entry>
<entry value="4" name="CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED">
<description>PUK is required to unblock SIM card.</description>
</entry>
</enum>
<enum name="WIFI_CONFIG_AP_MODE">
<description>WiFi Mode.</description>
<entry value="0" name="WIFI_CONFIG_AP_MODE_UNDEFINED">
<description>WiFi mode is undefined.</description>
</entry>
<entry value="1" name="WIFI_CONFIG_AP_MODE_AP">
<description>WiFi configured as an access point.</description>
</entry>
<entry value="2" name="WIFI_CONFIG_AP_MODE_STATION">
<description>WiFi configured as a station connected to an existing local WiFi network.</description>
</entry>
<entry value="3" name="WIFI_CONFIG_AP_MODE_DISABLED">
<description>WiFi disabled.</description>
</entry>
</enum>
<enum name="COMP_METADATA_TYPE">
<description>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.</description>
<entry value="0" name="COMP_METADATA_TYPE_GENERAL">
<description>General 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.</description>
</entry>
<entry value="1" name="COMP_METADATA_TYPE_PARAMETER">
<description>Parameter meta data.</description>
</entry>
<entry value="2" name="COMP_METADATA_TYPE_COMMANDS">
<description>Meta data that specifies which commands and command parameters the vehicle supports. (WIP)</description>
</entry>
<entry value="3" name="COMP_METADATA_TYPE_PERIPHERALS">
<description>Meta data that specifies external non-MAVLink peripherals.</description>
</entry>
<entry value="4" name="COMP_METADATA_TYPE_EVENTS">
<description>Meta data for the events interface.</description>
</entry>
<entry value="5" name="COMP_METADATA_TYPE_ACTUATORS">
<description>Meta data for actuator configuration (motors, servos and vehicle geometry) and testing.</description>
</entry>
</enum>
<enum name="ACTUATOR_CONFIGURATION">
<description>Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands.</description>
<entry value="0" name="ACTUATOR_CONFIGURATION_NONE">
<description>Do nothing.</description>
</entry>
<entry value="1" name="ACTUATOR_CONFIGURATION_BEEP">
<description>Command the actuator to beep now.</description>
</entry>
<entry value="2" name="ACTUATOR_CONFIGURATION_3D_MODE_ON">
<description>Permanently set the actuator (ESC) to 3D mode (reversible thrust).</description>
</entry>
<entry value="3" name="ACTUATOR_CONFIGURATION_3D_MODE_OFF">
<description>Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust).</description>
</entry>
<entry value="4" name="ACTUATOR_CONFIGURATION_SPIN_DIRECTION1">
<description>Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise).</description>
</entry>
<entry value="5" name="ACTUATOR_CONFIGURATION_SPIN_DIRECTION2">
<description>Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1).</description>
</entry>
</enum>
<enum name="ACTUATOR_OUTPUT_FUNCTION">
<description>Actuator output function. Values greater or equal to 1000 are autopilot-specific.</description>
<entry value="0" name="ACTUATOR_OUTPUT_FUNCTION_NONE">
<description>No function (disabled).</description>
</entry>
<entry value="1" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR1">
<description>Motor 1</description>
</entry>
<entry value="2" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR2">
<description>Motor 2</description>
</entry>
<entry value="3" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR3">
<description>Motor 3</description>
</entry>
<entry value="4" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR4">
<description>Motor 4</description>
</entry>
<entry value="5" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR5">
<description>Motor 5</description>
</entry>
<entry value="6" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR6">
<description>Motor 6</description>
</entry>
<entry value="7" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR7">
<description>Motor 7</description>
</entry>
<entry value="8" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR8">
<description>Motor 8</description>
</entry>
<entry value="9" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR9">
<description>Motor 9</description>
</entry>
<entry value="10" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR10">
<description>Motor 10</description>
</entry>
<entry value="11" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR11">
<description>Motor 11</description>
</entry>
<entry value="12" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR12">
<description>Motor 12</description>
</entry>
<entry value="13" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR13">
<description>Motor 13</description>
</entry>
<entry value="14" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR14">
<description>Motor 14</description>
</entry>
<entry value="15" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR15">
<description>Motor 15</description>
</entry>
<entry value="16" name="ACTUATOR_OUTPUT_FUNCTION_MOTOR16">
<description>Motor 16</description>
</entry>
<entry value="33" name="ACTUATOR_OUTPUT_FUNCTION_SERVO1">
<description>Servo 1</description>
</entry>
<entry value="34" name="ACTUATOR_OUTPUT_FUNCTION_SERVO2">
<description>Servo 2</description>
</entry>
<entry value="35" name="ACTUATOR_OUTPUT_FUNCTION_SERVO3">
<description>Servo 3</description>
</entry>
<entry value="36" name="ACTUATOR_OUTPUT_FUNCTION_SERVO4">
<description>Servo 4</description>
</entry>
<entry value="37" name="ACTUATOR_OUTPUT_FUNCTION_SERVO5">
<description>Servo 5</description>
</entry>
<entry value="38" name="ACTUATOR_OUTPUT_FUNCTION_SERVO6">
<description>Servo 6</description>
</entry>
<entry value="39" name="ACTUATOR_OUTPUT_FUNCTION_SERVO7">
<description>Servo 7</description>
</entry>
<entry value="40" name="ACTUATOR_OUTPUT_FUNCTION_SERVO8">
<description>Servo 8</description>
</entry>
<entry value="41" name="ACTUATOR_OUTPUT_FUNCTION_SERVO9">
<description>Servo 9</description>
</entry>
<entry value="42" name="ACTUATOR_OUTPUT_FUNCTION_SERVO10">
<description>Servo 10</description>
</entry>
<entry value="43" name="ACTUATOR_OUTPUT_FUNCTION_SERVO11">
<description>Servo 11</description>
</entry>
<entry value="44" name="ACTUATOR_OUTPUT_FUNCTION_SERVO12">
<description>Servo 12</description>
</entry>
<entry value="45" name="ACTUATOR_OUTPUT_FUNCTION_SERVO13">
<description>Servo 13</description>
</entry>
<entry value="46" name="ACTUATOR_OUTPUT_FUNCTION_SERVO14">
<description>Servo 14</description>
</entry>
<entry value="47" name="ACTUATOR_OUTPUT_FUNCTION_SERVO15">
<description>Servo 15</description>
</entry>
<entry value="48" name="ACTUATOR_OUTPUT_FUNCTION_SERVO16">
<description>Servo 16</description>
</entry>
</enum>
<enum name="AUTOTUNE_AXIS" bitmask="true">
<description>Enable axes that will be tuned via autotuning. Used in MAV_CMD_DO_AUTOTUNE_ENABLE.</description>
<entry value="0" name="AUTOTUNE_AXIS_DEFAULT">
<description>Flight stack tunes axis according to its default settings.</description>
</entry>
<entry value="1" name="AUTOTUNE_AXIS_ROLL">
<description>Autotune roll axis.</description>
</entry>
<entry value="2" name="AUTOTUNE_AXIS_PITCH">
<description>Autotune pitch axis.</description>
</entry>
<entry value="4" name="AUTOTUNE_AXIS_YAW">
<description>Autotune yaw axis.</description>
</entry>
</enum>
<enum name="PREFLIGHT_STORAGE_PARAMETER_ACTION">
<description>
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.)
</description>
<entry value="0" name="PARAM_READ_PERSISTENT">
<description>Read all parameters from persistent storage. Replaces values in volatile storage.</description>
</entry>
<entry value="1" name="PARAM_WRITE_PERSISTENT">
<description>Write all parameter values to persistent storage (flash/EEPROM)</description>
</entry>
<entry value="2" name="PARAM_RESET_CONFIG_DEFAULT">
<description>Reset 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.</description>
</entry>
<entry value="3" name="PARAM_RESET_SENSOR_DEFAULT">
<description>Reset only sensor calibration parameters to factory defaults (or firmware default if not available)</description>
</entry>
<entry value="4" name="PARAM_RESET_ALL_DEFAULT">
<description>Reset all parameters, including operation counters, to default values</description>
</entry>
</enum>
<enum name="PREFLIGHT_STORAGE_MISSION_ACTION">
<description>
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.)
</description>
<entry value="0" name="MISSION_READ_PERSISTENT">
<description>Read current mission data from persistent storage</description>
</entry>
<entry value="1" name="MISSION_WRITE_PERSISTENT">
<description>Write current mission data to persistent storage</description>
</entry>
<entry value="2" name="MISSION_RESET_DEFAULT">
<description>Erase all mission data stored on the vehicle (both persistent and volatile storage)</description>
</entry>
</enum>
<!-- The MAV_CMD enum entries describe either: -->
<!-- * the data payload of mission items (as used in the MISSION_ITEM_INT message) -->
<!-- * the data payload of mavlink commands (as used in the COMMAND_INT and COMMAND_LONG messages) -->
<!-- ALL the entries in the MAV_CMD enum have a maximum of 7 parameters -->
<enum name="MAV_CMD">
<description>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</description>
<entry value="16" name="MAV_CMD_NAV_WAYPOINT" hasLocation="true" isDestination="true">
<description>Navigate to waypoint.</description>
<param index="1" label="Hold" units="s" minValue="0">Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
<param index="2" label="Accept Radius" units="m" minValue="0">Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)</param>
<param index="3" label="Pass Radius" units="m">0 to pass through the WP, if &gt; 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param>
<param index="4" label="Yaw" units="deg">Desired 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.).</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM" hasLocation="true" isDestination="true">
<description>Loiter around this waypoint an unlimited amount of time</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3" label="Radius" units="m">Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise</param>
<param index="4" label="Yaw" units="deg">Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="18" name="MAV_CMD_NAV_LOITER_TURNS" hasLocation="true" isDestination="true">
<description>Loiter around this waypoint for X turns</description>
<param index="1" label="Turns" minValue="0">Number of turns.</param>
<param index="2" label="Heading Required" minValue="0" maxValue="1" increment="1">Leave loiter circle only once heading towards the next waypoint (0 = False)</param>
<param index="3" label="Radius" units="m">Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise</param>
<param index="4" label="Xtrack Location">Loiter 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.</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="19" name="MAV_CMD_NAV_LOITER_TIME" hasLocation="true" isDestination="true">
<description>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.</description>
<param index="1" label="Time" units="s" minValue="0">Loiter time (only starts once Lat, Lon and Alt is reached).</param>
<param index="2" label="Heading Required" minValue="0" maxValue="1" increment="1">Leave loiter circle only once heading towards the next waypoint (0 = False)</param>
<param index="3" label="Radius" units="m">Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.</param>
<param index="4" label="Xtrack Location">Loiter 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.</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH" hasLocation="false" isDestination="false">
<description>Return to launch location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="21" name="MAV_CMD_NAV_LAND" hasLocation="true" isDestination="true">
<description>Land at location.</description>
<param index="1" label="Abort Alt" units="m">Minimum target altitude if landing is aborted (0 = undefined/use system default).</param>
<param index="2" label="Land Mode" enum="PRECISION_LAND_MODE">Precision land mode.</param>
<param index="3">Empty.</param>
<param index="4" label="Yaw Angle" units="deg">Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).</param>
<param index="5" label="Latitude">Latitude.</param>
<param index="6" label="Longitude">Longitude.</param>
<param index="7" label="Altitude" units="m">Landing altitude (ground level in current frame).</param>
</entry>
<entry value="22" name="MAV_CMD_NAV_TAKEOFF" hasLocation="true" isDestination="true">
<description>Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode.</description>
<param index="1" label="Pitch" units="deg">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4" label="Yaw" units="deg">Yaw 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.).</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="23" name="MAV_CMD_NAV_LAND_LOCAL" hasLocation="true" isDestination="true">
<description>Land at local position (local frame only)</description>
<param index="1" label="Target" minValue="0" increment="1">Landing target number (if available)</param>
<param index="2" label="Offset" units="m" minValue="0">Maximum 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 land</param>
<param index="3" label="Descend Rate" units="m/s">Landing descend rate</param>
<param index="4" label="Yaw" units="rad">Desired yaw angle</param>
<param index="5" label="Y Position" units="m">Y-axis position</param>
<param index="6" label="X Position" units="m">X-axis position</param>
<param index="7" label="Z Position" units="m">Z-axis / ground level position</param>
</entry>
<entry value="24" name="MAV_CMD_NAV_TAKEOFF_LOCAL" hasLocation="true" isDestination="true">
<description>Takeoff from local position (local frame only)</description>
<param index="1" label="Pitch" units="rad">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<param index="2">Empty</param>
<param index="3" label="Ascend Rate" units="m/s">Takeoff ascend rate</param>
<param index="4" label="Yaw" units="rad">Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these</param>
<param index="5" label="Y Position" units="m">Y-axis position</param>
<param index="6" label="X Position" units="m">X-axis position</param>
<param index="7" label="Z Position" units="m">Z-axis position</param>
</entry>
<entry value="25" name="MAV_CMD_NAV_FOLLOW" hasLocation="true" isDestination="false">
<description>Vehicle following, i.e. this waypoint represents the position of a moving vehicle</description>
<param index="1" label="Following" increment="1">Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation</param>
<param index="2" label="Ground Speed" units="m/s">Ground speed of vehicle to be followed</param>
<param index="3" label="Radius" units="m">Radius around waypoint. If positive loiter clockwise, else counter-clockwise</param>
<param index="4" label="Yaw" units="deg">Desired yaw angle.</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="30" name="MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT" hasLocation="false" isDestination="true">
<description>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.</description>
<param index="1" label="Action" minValue="0" maxValue="2" increment="1">Climb 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.</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7" label="Altitude" units="m">Desired altitude</param>
</entry>
<entry value="31" name="MAV_CMD_NAV_LOITER_TO_ALT" hasLocation="true" isDestination="true">
<description>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.</description>
<param index="1" label="Heading Required" minValue="0" maxValue="1" increment="1">Leave loiter circle only once heading towards the next waypoint (0 = False)</param>
<param index="2" label="Radius" units="m">Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.</param>
<param index="3">Empty</param>
<param index="4" label="Xtrack Location" minValue="0" maxValue="1" increment="1">Loiter 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.</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="32" name="MAV_CMD_DO_FOLLOW" hasLocation="false" isDestination="false">
<description>Begin following a target</description>
<param index="1" label="System ID" minValue="0" maxValue="255" increment="1">System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.</param>
<param index="2">Reserved</param>
<param index="3">Reserved</param>
<param index="4" label="Altitude Mode" minValue="0" maxValue="2" increment="1">Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.</param>
<param index="5" label="Altitude" units="m">Altitude above home. (used if mode=2)</param>
<param index="6">Reserved</param>
<param index="7" label="Time to Land" units="s" minValue="0">Time to land in which the MAV should go to the default position hold mode after a message RX timeout.</param>
</entry>
<entry value="33" name="MAV_CMD_DO_FOLLOW_REPOSITION" hasLocation="false" isDestination="false">
<description>Reposition the MAV after a follow target command has been sent</description>
<param index="1" label="Camera Q1">Camera q1 (where 0 is on the ray from the camera to the tracking device)</param>
<param index="2" label="Camera Q2">Camera q2</param>
<param index="3" label="Camera Q3">Camera q3</param>
<param index="4" label="Camera Q4">Camera q4</param>
<param index="5" label="Altitude Offset" units="m">altitude offset from target</param>
<param index="6" label="X Offset" units="m">X offset from target</param>
<param index="7" label="Y Offset" units="m">Y offset from target</param>
</entry>
<entry value="34" name="MAV_CMD_DO_ORBIT" hasLocation="true" isDestination="true">
<wip/>
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
<description>Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults.</description>
<param index="1" label="Radius" units="m">Radius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting.</param>
<param index="2" label="Velocity" units="m/s">Tangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting.</param>
<param index="3" label="Yaw Behavior" enum="ORBIT_YAW_BEHAVIOUR">Yaw behavior of the vehicle.</param>
<param index="4" label="Orbits" units="rad" minValue="0" default="0">Orbit 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.</param>
<param index="5" label="Latitude/X">Center 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.</param>
<param index="6" label="Longitude/Y">Center 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.</param>
<param index="7" label="Altitude/Z">Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude.</param>
</entry>
<entry value="80" name="MAV_CMD_NAV_ROI" hasLocation="true" isDestination="false">
<deprecated since="2018-01" replaced_by="MAV_CMD_DO_SET_ROI_*"/>
<description>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.</description>
<param index="1" label="ROI Mode" enum="MAV_ROI">Region of interest mode.</param>
<param index="2" label="WP Index" minValue="0" increment="1">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<param index="3" label="ROI Index" minValue="0" increment="1">ROI index (allows a vehicle to manage multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5" label="X">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6" label="Y">y</param>
<param index="7" label="Z">z</param>
</entry>
<entry value="81" name="MAV_CMD_NAV_PATHPLANNING" hasLocation="true" isDestination="true">
<description>Control autonomous path planning on the MAV.</description>
<param index="1" label="Local Ctrl" minValue="0" maxValue="2" increment="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param>
<param index="2" label="Global Ctrl" minValue="0" maxValue="3" increment="1">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param>
<param index="3">Empty</param>
<param index="4" label="Yaw" units="deg">Yaw angle at goal</param>
<param index="5" label="Latitude/X">Latitude/X of goal</param>
<param index="6" label="Longitude/Y">Longitude/Y of goal</param>
<param index="7" label="Altitude/Z">Altitude/Z of goal</param>
</entry>
<entry value="82" name="MAV_CMD_NAV_SPLINE_WAYPOINT" hasLocation="true" isDestination="true">
<description>Navigate to waypoint using a spline path.</description>
<param index="1" label="Hold" units="s" minValue="0">Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5" label="Latitude/X">Latitude/X of goal</param>
<param index="6" label="Longitude/Y">Longitude/Y of goal</param>
<param index="7" label="Altitude/Z">Altitude/Z of goal</param>
</entry>
<entry value="84" name="MAV_CMD_NAV_VTOL_TAKEOFF" hasLocation="true" isDestination="true">
<description>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.).</description>
<param index="1">Empty</param>
<param index="2" label="Transition Heading" enum="VTOL_TRANSITION_HEADING">Front transition heading.</param>
<param index="3">Empty</param>
<param index="4" label="Yaw Angle" units="deg">Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="85" name="MAV_CMD_NAV_VTOL_LAND" hasLocation="true" isDestination="true">
<description>Land using VTOL mode</description>
<param index="1" label="Land Options" enum="NAV_VTOL_LAND_OPTIONS">Landing behaviour.</param>
<param index="2">Empty</param>
<param index="3" label="Approach Altitude" units="m">Approach altitude (with the same reference as the Altitude field). NaN if unspecified.</param>
<param index="4" label="Yaw" units="deg">Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Ground Altitude" units="m">Altitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value).</param>
</entry>
<!-- IDs 90 and 91 are reserved until the end of 2014,
as they were used in some conflicting proposals
between PX4 and ArduPilot and need to be kept
unused to prevent errors -->
<entry value="92" name="MAV_CMD_NAV_GUIDED_ENABLE" hasLocation="false" isDestination="false">
<description>hand control over to an external controller</description>
<param index="1" label="Enable" minValue="0" maxValue="1" increment="1">On / Off (&gt; 0.5f on)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="93" name="MAV_CMD_NAV_DELAY" hasLocation="false" isDestination="false">
<description>Delay the next navigation command a number of seconds or until a specified time</description>
<param index="1" label="Delay" units="s" minValue="-1" increment="1">Delay (-1 to enable time-of-day fields)</param>
<param index="2" label="Hour" minValue="-1" maxValue="23" increment="1">hour (24h format, UTC, -1 to ignore)</param>
<param index="3" label="Minute" minValue="-1" maxValue="59" increment="1">minute (24h format, UTC, -1 to ignore)</param>
<param index="4" label="Second" minValue="-1" maxValue="59" increment="1">second (24h format, UTC, -1 to ignore)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="94" name="MAV_CMD_NAV_PAYLOAD_PLACE" hasLocation="true" isDestination="true">
<description>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.</description>
<param index="1" label="Max Descent" units="m" minValue="0">Maximum distance to descend.</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="95" name="MAV_CMD_NAV_LAST" hasLocation="false" isDestination="false">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="112" name="MAV_CMD_CONDITION_DELAY" hasLocation="false" isDestination="false">
<description>Delay mission state machine.</description>
<param index="1" label="Delay" units="s" minValue="0">Delay</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT" hasLocation="false" isDestination="true">
<description>Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached.</description>
<param index="1" label="Rate" units="m/s">Descent / Ascend rate.</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7" label="Altitude" units="m">Target Altitude</param>
</entry>
<entry value="114" name="MAV_CMD_CONDITION_DISTANCE" hasLocation="false" isDestination="false">
<description>Delay mission state machine until within desired distance of next NAV point.</description>
<param index="1" label="Distance" units="m" minValue="0">Distance.</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="115" name="MAV_CMD_CONDITION_YAW" hasLocation="false" isDestination="false">
<description>Reach a certain target angle.</description>
<param index="1" label="Angle" units="deg">target angle, 0 is north</param>
<param index="2" label="Angular Speed" units="deg/s">angular speed</param>
<param index="3" label="Direction" minValue="-1" maxValue="1" increment="2">direction: -1: counter clockwise, 1: clockwise</param>
<param index="4" label="Relative" minValue="0" maxValue="1" increment="1">0: absolute angle, 1: relative offset</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="159" name="MAV_CMD_CONDITION_LAST" hasLocation="false" isDestination="false">
<description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="176" name="MAV_CMD_DO_SET_MODE" hasLocation="false" isDestination="false">
<description>Set system mode.</description>
<param index="1" label="Mode" enum="MAV_MODE">Mode</param>
<param index="2" label="Custom Mode">Custom mode - this is system specific, please refer to the individual autopilot specifications for details.</param>
<param index="3" label="Custom Submode">Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="177" name="MAV_CMD_DO_JUMP" hasLocation="false" isDestination="false">
<description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description>
<param index="1" label="Number" minValue="0" increment="1">Sequence number</param>
<param index="2" label="Repeat" minValue="0" increment="1">Repeat count</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="178" name="MAV_CMD_DO_CHANGE_SPEED" hasLocation="false" isDestination="false">
<description>Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change.</description>
<param index="1" label="Speed Type" minValue="0" maxValue="3" increment="1">Speed type (0=Airspeed, 1=Ground Speed, 2=Climb Speed, 3=Descent Speed)</param>
<param index="2" label="Speed" units="m/s" minValue="-2">Speed (-1 indicates no change, -2 indicates return to default vehicle speed)</param>
<param index="3" label="Throttle" units="%" minValue="-2">Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)</param>
<param index="4" reserved="true" default="0"/>
<param index="5" reserved="true" default="0"/>
<param index="6" reserved="true" default="0"/>
<param index="7" reserved="true" default="0"/>
</entry>
<entry value="179" name="MAV_CMD_DO_SET_HOME" hasLocation="true" isDestination="false">
<description>
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).
</description>
<param index="1" label="Use Current" minValue="0" maxValue="1" increment="1">Use current (1=use current location, 0=use specified location)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4" label="Yaw" units="deg">Yaw angle. NaN to use default heading</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="180" name="MAV_CMD_DO_SET_PARAMETER" hasLocation="false" isDestination="false">
<description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description>
<param index="1" label="Number" minValue="0" increment="1">Parameter number</param>
<param index="2" label="Value">Parameter value</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="181" name="MAV_CMD_DO_SET_RELAY" hasLocation="false" isDestination="false">
<description>Set a relay to a condition.</description>
<param index="1" label="Instance" minValue="0" increment="1">Relay instance number.</param>
<param index="2" label="Setting" minValue="0" increment="1">Setting. (1=on, 0=off, others possible depending on system hardware)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="182" name="MAV_CMD_DO_REPEAT_RELAY" hasLocation="false" isDestination="false">
<description>Cycle a relay on and off for a desired number of cycles with a desired period.</description>
<param index="1" label="Instance" minValue="0" increment="1">Relay instance number.</param>
<param index="2" label="Count" minValue="1" increment="1">Cycle count.</param>
<param index="3" label="Time" units="s" minValue="0">Cycle time.</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="183" name="MAV_CMD_DO_SET_SERVO" hasLocation="false" isDestination="false">
<description>Set a servo to a desired PWM value.</description>
<param index="1" label="Instance" minValue="0" increment="1">Servo instance number.</param>
<param index="2" label="PWM" units="us" minValue="0" increment="1">Pulse Width Modulation.</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="184" name="MAV_CMD_DO_REPEAT_SERVO" hasLocation="false" isDestination="false">
<description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description>
<param index="1" label="Instance" minValue="0" increment="1">Servo instance number.</param>
<param index="2" label="PWM" units="us" minValue="0" increment="1">Pulse Width Modulation.</param>
<param index="3" label="Count" minValue="1" increment="1">Cycle count.</param>
<param index="4" label="Time" units="s" minValue="0">Cycle time.</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="185" name="MAV_CMD_DO_FLIGHTTERMINATION" hasLocation="false" isDestination="false">
<description>Terminate flight immediately.
Flight termination immediately and irreversably 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 (&lt; 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.
</description>
<param index="1" label="Terminate" minValue="0" maxValue="1" increment="1">Flight termination activated if &gt; 0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED.</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="186" name="MAV_CMD_DO_CHANGE_ALTITUDE" hasLocation="false" isDestination="false">
<description>Change altitude set point.</description>
<param index="1" label="Altitude" units="m">Altitude.</param>
<param index="2" label="Frame" enum="MAV_FRAME">Frame of new altitude.</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="187" name="MAV_CMD_DO_SET_ACTUATOR" hasLocation="false" isDestination="false">
<description>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).</description>
<param index="1" label="Actuator 1" minValue="-1" maxValue="1">Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="2" label="Actuator 2" minValue="-1" maxValue="1">Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="3" label="Actuator 3" minValue="-1" maxValue="1">Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="4" label="Actuator 4" minValue="-1" maxValue="1">Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="5" label="Actuator 5" minValue="-1" maxValue="1">Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="6" label="Actuator 6" minValue="-1" maxValue="1">Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.</param>
<param index="7" label="Index" minValue="0" increment="1">Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)</param>
</entry>
<entry value="189" name="MAV_CMD_DO_LAND_START" hasLocation="true" isDestination="false">
<description>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.
</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="190" name="MAV_CMD_DO_RALLY_LAND" hasLocation="false" isDestination="false">
<description>Mission command to perform a landing from a rally point.</description>
<param index="1" label="Altitude" units="m">Break altitude</param>
<param index="2" label="Speed" units="m/s">Landing speed</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="191" name="MAV_CMD_DO_GO_AROUND" hasLocation="false" isDestination="false">
<description>Mission command to safely abort an autonomous landing.</description>
<param index="1" label="Altitude" units="m">Altitude</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="192" name="MAV_CMD_DO_REPOSITION" hasLocation="true" isDestination="true">
<description>Reposition the vehicle to a specific WGS84 global position.</description>
<param index="1" label="Speed" units="m/s" minValue="-1">Ground speed, less than 0 (-1) for default</param>
<param index="2" label="Bitmask" enum="MAV_DO_REPOSITION_FLAGS">Bitmask of option flags.</param>
<param index="3" label="Radius" units="m">Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored. </param>
<param index="4" label="Yaw" units="deg">Yaw 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)</param>
<param index="5" label="Latitude">Latitude</param>
<param index="6" label="Longitude">Longitude</param>
<param index="7" label="Altitude" units="m">Altitude</param>
</entry>
<entry value="193" name="MAV_CMD_DO_PAUSE_CONTINUE" hasLocation="false" isDestination="false">
<description>If in a GPS controlled position mode, hold the current position or continue.</description>
<param index="1" label="Continue" minValue="0" maxValue="1" increment="1">0: 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.</param>
<param index="2">Reserved</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Reserved</param>
<param index="6">Reserved</param>
<param index="7">Reserved</param>
</entry>
<entry value="194" name="MAV_CMD_DO_SET_REVERSE" hasLocation="false" isDestination="false">
<description>Set moving direction to forward or reverse.</description>
<param index="1" label="Reverse" minValue="0" maxValue="1" increment="1">Direction (0=Forward, 1=Reverse)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="195" name="MAV_CMD_DO_SET_ROI_LOCATION" hasLocation="true" isDestination="false">
<description>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.</description>
<param index="1" label="Gimbal device ID">Component 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).</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5" label="Latitude" units="degE7">Latitude of ROI location</param>
<param index="6" label="Longitude" units="degE7">Longitude of ROI location</param>
<param index="7" label="Altitude" units="m">Altitude of ROI location</param>
</entry>
<entry value="196" name="MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Gimbal device ID">Component 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).</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5" label="Pitch Offset">Pitch offset from next waypoint, positive pitching up</param>
<param index="6" label="Roll Offset">Roll offset from next waypoint, positive rolling to the right</param>
<param index="7" label="Yaw Offset">Yaw offset from next waypoint, positive yawing to the right</param>
</entry>
<entry value="197" name="MAV_CMD_DO_SET_ROI_NONE" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Gimbal device ID">Component 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).</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="198" name="MAV_CMD_DO_SET_ROI_SYSID">
<description>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.</description>
<param index="1" label="System ID" minValue="1" maxValue="255" increment="1">System ID</param>
<param index="2" label="Gimbal device ID">Component 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).</param>
</entry>
<entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO" hasLocation="false" isDestination="false">
<description>Control onboard camera system.</description>
<param index="1" label="ID" minValue="-1" increment="1">Camera ID (-1 for all)</param>
<param index="2" label="Transmission" minValue="0" maxValue="2" increment="1">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="3" label="Interval" units="s" minValue="0">Transmission mode: 0: video stream, &gt;0: single images every n seconds</param>
<param index="4" label="Recording" minValue="0" maxValue="2" increment="1">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="201" name="MAV_CMD_DO_SET_ROI" hasLocation="true" isDestination="false">
<deprecated since="2018-01" replaced_by="MAV_CMD_DO_SET_ROI_*"/>
<description>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.</description>
<param index="1" label="ROI Mode" enum="MAV_ROI">Region of interest mode.</param>
<param index="2" label="WP Index" minValue="0" increment="1">Waypoint index/ target ID (depends on param 1).</param>
<param index="3" label="ROI Index" minValue="0" increment="1">Region of interest index. (allows a vehicle to manage multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5">MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude</param>
<param index="6">MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude</param>
<param index="7">MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude</param>
</entry>
<!-- Camera Controller Mission Commands Enumeration -->
<entry value="202" name="MAV_CMD_DO_DIGICAM_CONFIGURE" hasLocation="false" isDestination="false">
<description>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 ).</description>
<param index="1" label="Mode" minValue="0" increment="1">Modes: P, TV, AV, M, Etc.</param>
<param index="2" label="Shutter Speed" minValue="0" increment="1">Shutter speed: Divisor number for one second.</param>
<param index="3" label="Aperture" minValue="0">Aperture: F stop number.</param>
<param index="4" label="ISO" minValue="0" increment="1">ISO number e.g. 80, 100, 200, Etc.</param>
<param index="5" label="Exposure">Exposure type enumerator.</param>
<param index="6" label="Command Identity">Command Identity.</param>
<param index="7" label="Engine Cut-off" units="ds" minValue="0" increment="1">Main engine cut-off time before camera trigger. (0 means no cut-off)</param>
</entry>
<entry value="203" name="MAV_CMD_DO_DIGICAM_CONTROL" hasLocation="false" isDestination="false">
<description>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 ).</description>
<param index="1" label="Session Control">Session control e.g. show/hide lens</param>
<param index="2" label="Zoom Absolute">Zoom's absolute position</param>
<param index="3" label="Zoom Relative">Zooming step value to offset zoom from the current position</param>
<param index="4" label="Focus">Focus Locking, Unlocking or Re-locking</param>
<param index="5" label="Shoot Command">Shooting Command</param>
<param index="6" label="Command Identity">Command Identity</param>
<param index="7" label="Shot ID">Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.</param>
</entry>
<!-- Camera Mount Mission Commands Enumeration -->
<entry value="204" name="MAV_CMD_DO_MOUNT_CONFIGURE" hasLocation="false" isDestination="false">
<deprecated since="2020-01" replaced_by="MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE">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.</deprecated>
<description>Mission command to configure a camera or antenna mount</description>
<param index="1" label="Mode" enum="MAV_MOUNT_MODE">Mount operation mode</param>
<param index="2" label="Stabilize Roll" minValue="0" maxValue="1" increment="1">stabilize roll? (1 = yes, 0 = no)</param>
<param index="3" label="Stabilize Pitch" minValue="0" maxValue="1" increment="1">stabilize pitch? (1 = yes, 0 = no)</param>
<param index="4" label="Stabilize Yaw" minValue="0" maxValue="1" increment="1">stabilize yaw? (1 = yes, 0 = no)</param>
<param index="5" label="Roll Input Mode">roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)</param>
<param index="6" label="Pitch Input Mode">pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)</param>
<param index="7" label="Yaw Input Mode">yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)</param>
</entry>
<!-- this one is messed up! altitude should be param 7, not param4 -->
<entry value="205" name="MAV_CMD_DO_MOUNT_CONTROL" hasLocation="false" isDestination="false">
<deprecated since="2020-01" replaced_by="MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW">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.</deprecated>
<description>Mission command to control a camera or antenna mount</description>
<param index="1" label="Pitch">pitch depending on mount mode (degrees or degrees/second depending on pitch input).</param>
<param index="2" label="Roll">roll depending on mount mode (degrees or degrees/second depending on roll input).</param>
<param index="3" label="Yaw">yaw depending on mount mode (degrees or degrees/second depending on yaw input).</param>
<param index="4" label="Altitude" units="m">altitude depending on mount mode.</param>
<param index="5" label="Latitude">latitude, set if appropriate mount mode.</param>
<param index="6" label="Longitude">longitude, set if appropriate mount mode.</param>
<param index="7" label="Mode" enum="MAV_MOUNT_MODE">Mount mode.</param>
</entry>
<entry value="206" name="MAV_CMD_DO_SET_CAM_TRIGG_DIST" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Distance" units="m" minValue="0">Camera trigger distance. 0 to stop triggering.</param>
<param index="2" label="Shutter" units="ms" minValue="-1" increment="1">Camera shutter integration time. -1 or 0 to ignore</param>
<param index="3" label="Trigger" minValue="0" maxValue="1" increment="1">Trigger camera once immediately. (0 = no trigger, 1 = trigger)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="207" name="MAV_CMD_DO_FENCE_ENABLE" hasLocation="false" isDestination="false">
<description>Mission command to enable the geofence</description>
<param index="1" label="Enable" minValue="0" maxValue="2" increment="1">enable? (0=disable, 1=enable, 2=disable_floor_only)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="208" name="MAV_CMD_DO_PARACHUTE" hasLocation="false" isDestination="false">
<description>Mission item/command to release a parachute or enable/disable auto release.</description>
<param index="1" label="Action" enum="PARACHUTE_ACTION">Action</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="209" name="MAV_CMD_DO_MOTOR_TEST" hasLocation="false" isDestination="false">
<description>Command to perform motor test.</description>
<param index="1" label="Instance" minValue="1" increment="1">Motor instance number (from 1 to max number of motors on the vehicle).</param>
<param index="2" label="Throttle Type" enum="MOTOR_TEST_THROTTLE_TYPE">Throttle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.)</param>
<param index="3" label="Throttle">Throttle value.</param>
<param index="4" label="Timeout" units="s" minValue="0">Timeout between tests that are run in sequence.</param>
<param index="5" label="Motor Count" minValue="0" increment="1">Motor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests.</param>
<param index="6" label="Test Order" enum="MOTOR_TEST_ORDER">Motor test order.</param>
<param index="7">Empty</param>
</entry>
<entry value="210" name="MAV_CMD_DO_INVERTED_FLIGHT" hasLocation="false" isDestination="false">
<description>Change to/from inverted flight.</description>
<param index="1" label="Inverted" minValue="0" maxValue="1" increment="1">Inverted flight. (0=normal, 1=inverted)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="211" name="MAV_CMD_DO_GRIPPER" hasLocation="false" isDestination="false">
<description>Mission command to operate a gripper.</description>
<param index="1" label="Instance" minValue="1" increment="1">Gripper instance number.</param>
<param index="2" label="Action" enum="GRIPPER_ACTIONS">Gripper action to perform.</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="212" name="MAV_CMD_DO_AUTOTUNE_ENABLE" hasLocation="false" isDestination="false">
<description>Enable/disable autotune.</description>
<param index="1" label="Enable" minValue="0" maxValue="1" increment="1">Enable (1: enable, 0:disable).</param>
<param index="2" label="Axis" enum="AUTOTUNE_AXIS">Specify which axis are autotuned. 0 indicates autopilot default settings.</param>
<param index="3">Empty.</param>
<param index="4">Empty.</param>
<param index="5">Empty.</param>
<param index="6">Empty.</param>
<param index="7">Empty.</param>
</entry>
<entry value="213" name="MAV_CMD_NAV_SET_YAW_SPEED" hasLocation="false" isDestination="false">
<description>Sets a desired vehicle turn angle and speed change.</description>
<param index="1" label="Yaw" units="deg">Yaw angle to adjust steering by.</param>
<param index="2" label="Speed" units="m/s">Speed.</param>
<param index="3" label="Angle" minValue="0" maxValue="1" increment="1">Final angle. (0=absolute, 1=relative)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="214" name="MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Trigger Cycle" units="ms" minValue="-1" increment="1">Camera trigger cycle time. -1 or 0 to ignore.</param>
<param index="2" label="Shutter Integration" units="ms" minValue="-1" increment="1">Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="220" name="MAV_CMD_DO_MOUNT_CONTROL_QUAT" hasLocation="false" isDestination="false">
<deprecated since="2020-01" replaced_by="MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW"/>
<description>Mission command to control a camera or antenna mount, using a quaternion as reference.</description>
<param index="1" label="Q1">quaternion param q1, w (1 in null-rotation)</param>
<param index="2" label="Q2">quaternion param q2, x (0 in null-rotation)</param>
<param index="3" label="Q3">quaternion param q3, y (0 in null-rotation)</param>
<param index="4" label="Q4">quaternion param q4, z (0 in null-rotation)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="221" name="MAV_CMD_DO_GUIDED_MASTER" hasLocation="false" isDestination="false">
<description>set id of master controller</description>
<param index="1" label="System ID" minValue="0" maxValue="255" increment="1">System ID</param>
<param index="2" label="Component ID" minValue="0" maxValue="255" increment="1">Component ID</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="222" name="MAV_CMD_DO_GUIDED_LIMITS" hasLocation="false" isDestination="false">
<description>Set limits for external control</description>
<param index="1" label="Timeout" units="s" minValue="0">Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.</param>
<param index="2" label="Min Altitude" units="m">Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.</param>
<param index="3" label="Max Altitude" units="m">Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.</param>
<param index="4" label="Horiz. Move Limit" units="m" minValue="0">Horizontal 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.</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="223" name="MAV_CMD_DO_ENGINE_CONTROL" hasLocation="false" isDestination="false">
<description>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</description>
<param index="1" label="Start Engine" minValue="0" maxValue="1" increment="1">0: Stop engine, 1:Start Engine</param>
<param index="2" label="Cold Start" minValue="0" maxValue="1" increment="1">0: Warm start, 1:Cold start. Controls use of choke where applicable</param>
<param index="3" label="Height Delay" units="m" minValue="0">Height 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.</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="224" name="MAV_CMD_DO_SET_MISSION_CURRENT" hasLocation="false" isDestination="false">
<description>
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).
</description>
<param index="1" label="Number" minValue="-1" increment="1">Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item).</param>
<param index="2" label="Reset Mission" minValue="0" maxValue="1" increment="1">Resets mission. 1: true, 0: false. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused".</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="240" name="MAV_CMD_DO_LAST" hasLocation="false" isDestination="false">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION" hasLocation="false" isDestination="false">
<description>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.</description>
<param index="1" label="Gyro Temperature" minValue="0" maxValue="3" increment="1">1: gyro calibration, 3: gyro temperature calibration</param>
<param index="2" label="Magnetometer" minValue="0" maxValue="1" increment="1">1: magnetometer calibration</param>
<param index="3" label="Ground Pressure" minValue="0" maxValue="1" increment="1">1: ground pressure calibration</param>
<param index="4" label="Remote Control" minValue="0" maxValue="1" increment="1">1: radio RC calibration, 2: RC trim calibration</param>
<param index="5" label="Accelerometer" minValue="0" maxValue="4" increment="1">1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration</param>
<param index="6" label="Compmot or Airspeed" minValue="0" maxValue="2" increment="1">1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration</param>
<param index="7" label="ESC or Baro" minValue="0" maxValue="3" increment="1">1: ESC calibration, 3: barometer temperature calibration</param>
</entry>
<entry value="242" name="MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS" hasLocation="false" isDestination="false">
<description>Set sensor offsets. This command will be only accepted if in pre-flight mode.</description>
<param index="1" label="Sensor Type" minValue="0" maxValue="6" increment="1">Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer</param>
<param index="2" label="X Offset">X axis offset (or generic dimension 1), in the sensor's raw units</param>
<param index="3" label="Y Offset">Y axis offset (or generic dimension 2), in the sensor's raw units</param>
<param index="4" label="Z Offset">Z axis offset (or generic dimension 3), in the sensor's raw units</param>
<param index="5" label="4th Dimension">Generic dimension 4, in the sensor's raw units</param>
<param index="6" label="5th Dimension">Generic dimension 5, in the sensor's raw units</param>
<param index="7" label="6th Dimension">Generic dimension 6, in the sensor's raw units</param>
</entry>
<entry value="243" name="MAV_CMD_PREFLIGHT_UAVCAN" hasLocation="false" isDestination="false">
<description>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).</description>
<param index="1" label="Actuator ID">1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.</param>
<param index="2">Reserved</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Reserved</param>
<param index="6">Reserved</param>
<param index="7">Reserved</param>
</entry>
<entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE" hasLocation="false" isDestination="false">
<description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description>
<param index="1" label="Parameter Storage" enum="PREFLIGHT_STORAGE_PARAMETER_ACTION">Action to perform on the persistent parameter storage</param>
<param index="2" label=