<description>Enumeration of possible mount operation modes</description>
<entryname="MAV_MOUNT_MODE_RETRACT"value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_NEUTRAL"value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry>
<entryname="MAV_MOUNT_MODE_MAVLINK_TARGETING"value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_RC_TARGETING"value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_GPS_POINT"value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
</enum>
<!-- ardupilot specific MAV_CMD_* commands -->
<enumname="MAV_CMD">
<!-- Camera Controller Mission Commands Enumeration -->
<description>Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations.</description>
<description>Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations.</description>
</entry>
</enum>
<enumname="MAVLINK_DATA_STREAM_TYPE">
<entryname="MAVLINK_DATA_STREAM_IMG_JPEG">
@ -431,6 +437,45 @@
@@ -431,6 +437,45 @@
<description/>
</entry>
</enum>
<!-- fenced mode enums -->
<enumname="FENCE_ACTION">
<entryname="FENCE_ACTION_NONE"value="0">
<description>Disable fenced mode</description>
</entry>
<entryname="FENCE_ACTION_GUIDED"value="1">
<description>Switched to guided mode to return point (fence point 0)</description>
</entry>
<entryname="FENCE_ACTION_REPORT"value="2">
<description>Report fence breach, but don't take action</description>
<description>Enumeration of possible mount operation modes</description>
<entryname="MAV_MOUNT_MODE_RETRACT"value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_NEUTRAL"value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.</description></entry>
<entryname="MAV_MOUNT_MODE_MAVLINK_TARGETING"value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_RC_TARGETING"value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
<entryname="MAV_MOUNT_MODE_GPS_POINT"value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
</enum>
<enumname="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.</description>
<entryvalue="16"name="MAV_CMD_NAV_WAYPOINT">
@ -703,6 +748,97 @@
@@ -703,6 +748,97 @@
<paramindex="6">y</param>
<paramindex="7">z</param>
</entry>
<!-- Camera Controller Mission Commands Enumeration -->
<description>Mission command to control a camera or antenna mount, using a quaternion as reference.</description>
<paramindex="1">q1 - quaternion param #1</param>
<paramindex="2">q2 - quaternion param #2</param>
<paramindex="3">q3 - quaternion param #3</param>
<paramindex="4">q4 - quaternion param #4</param>
<paramindex="5">Empty</param>
<paramindex="6">Empty</param>
<paramindex="7">Empty</param>
</entry>
<entryvalue="240"name="MAV_CMD_DO_LAST">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<paramindex="1">Empty</param>
@ -1046,7 +1182,7 @@
@@ -1046,7 +1182,7 @@
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<fieldtype="uint8_t"name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<fieldtype="uint8_t"name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<fieldtype="uint8_t"name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field>
<fieldtype="uint8_t"name="base_mode">System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h</field>
<fieldtype="uint32_t"name="custom_mode">A bitfield for use for autopilot-specific flags.</field>
<fieldtype="uint8_t"name="system_status">System status flag, see MAV_STATE ENUM</field>
<fieldtype="uint8_t_mavlink_version"name="mavlink_version">MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version</field>
@ -1100,7 +1236,7 @@
@@ -1100,7 +1236,7 @@
<messageid="11"name="SET_MODE">
<description>Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<fieldtype="uint8_t"name="target_system">The system setting the mode</field>
<fieldtype="uint8_t"name="base_mode">The new base mode</field>
<fieldtype="uint8_t"name="base_mode"enum="MAV_MODE">The new base mode</field>
<fieldtype="uint32_t"name="custom_mode">The new autopilot-specific mode. This field can be ignored by an autopilot.</field>
</message>
<messageid="20"name="PARAM_REQUEST_READ">
@ -1119,7 +1255,7 @@
@@ -1119,7 +1255,7 @@
<description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description>
<fieldtype="char[16]"name="param_id">Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string</field>
<fieldtype="char[16]"name="param_id">Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string</field>
<fieldtype="uint8_t"name="param_type">Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.</field>
<fieldtype="uint8_t"name="param_type"enum="MAV_PARAM_TYPE">Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.</field>
</message>
<messageid="24"name="GPS_RAW_INT">
<description>The global position, as returned by the Global Positioning System (GPS). This is
@ -1352,7 +1488,7 @@
@@ -1352,7 +1488,7 @@
<description>Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description>
<description>As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
@ -1405,7 +1541,7 @@
@@ -1405,7 +1541,7 @@
<description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description>
<fieldtype="uint8_t"name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<fieldtype="uint8_t"name="frame"enum="MAV_FRAME">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<fieldtype="float"name="p1x">x position 1 / Latitude 1</field>
<fieldtype="float"name="p1y">y position 1 / Longitude 1</field>
<fieldtype="float"name="p1z">z position 1 / Altitude 1</field>
@ -1415,7 +1551,7 @@
@@ -1415,7 +1551,7 @@
</message>
<messageid="55"name="SAFETY_ALLOWED_AREA">
<description>Read out the safety zone the MAV currently assumes.</description>
<fieldtype="uint8_t"name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<fieldtype="uint8_t"name="frame"enum="MAV_FRAME">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<fieldtype="float"name="p1x">x position 1 / Latitude 1</field>
<fieldtype="float"name="p1y">y position 1 / Longitude 1</field>
<fieldtype="float"name="p1z">z position 1 / Altitude 1</field>
@ -1580,7 +1716,7 @@
@@ -1580,7 +1716,7 @@
<description>Send a command with up to seven parameters to the MAV</description>
<fieldtype="uint8_t"name="target_system">System which should execute the command</field>
<fieldtype="uint8_t"name="target_component">Component which should execute the command, 0 for all components</field>
<fieldtype="uint16_t"name="command">Command ID, as defined by MAV_CMD enum.</field>
<fieldtype="uint16_t"name="command"enum="MAV_CMD">Command ID, as defined by MAV_CMD enum.</field>
<fieldtype="uint8_t"name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field>
<fieldtype="float"name="param1">Parameter 1, as defined by MAV_CMD enum.</field>
<fieldtype="float"name="param2">Parameter 2, as defined by MAV_CMD enum.</field>
@ -1592,7 +1728,7 @@
@@ -1592,7 +1728,7 @@
</message>
<messageid="77"name="COMMAND_ACK">
<description>Report status of a command. Includes feedback wether the command was executed.</description>
<fieldtype="uint16_t"name="command">Command ID, as defined by MAV_CMD enum.</field>
<fieldtype="uint16_t"name="command"enum="MAV_CMD">Command ID, as defined by MAV_CMD enum.</field>
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<fieldtype="uint8_t"name="severity">Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.</field>
<fieldtype="uint8_t"name="severity"enum="MAV_SEVERITY">Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.</field>
<fieldtype="char[50]"name="text">Status text message, without null termination character</field>