<description>0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.</description>
<description>0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.</description>
<description>0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.</description>
<description>These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.</description>
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entryvalue="208"name="MAV_MODE_STABILIZE_ARMED">
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entryvalue="64"name="MAV_MODE_MANUAL_DISARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entryvalue="192"name="MAV_MODE_MANUAL_ARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entryvalue="88"name="MAV_MODE_GUIDED_DISARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entryvalue="216"name="MAV_MODE_GUIDED_ARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entryvalue="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 MISSIONs)</description>
</entry>
<entryvalue="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 MISSIONs)</description>
</entry>
<entryvalue="66"name="MAV_MODE_TEST_DISARMED">
<description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description>
</entry>
<entryvalue="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>
<enumname="MAV_STATE">
<entryvalue="0"name="MAV_STATE_UNINIT">
<description>Uninitialized system, state is unknown.</description>
</entry>
<entryname="MAV_STATE_BOOT">
<description>System is booting up.</description>
</entry>
<entryname="MAV_STATE_CALIBRATING">
<description>System is calibrating and not flight-ready.</description>
</entry>
<entryname="MAV_STATE_STANDBY">
<description>System is grounded and on standby. It can be launched any time.</description>
</entry>
<entryname="MAV_STATE_ACTIVE">
<description>System is active and might be already airborne. Motors are engaged.</description>
</entry>
<entryname="MAV_STATE_CRITICAL">
<description>System is in a non-normal flight mode. It can however still navigate.</description>
</entry>
<entryname="MAV_STATE_EMERGENCY">
<description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description>
</entry>
<entryname="MAV_STATE_POWEROFF">
<description>System just initialized its power-down sequence, will shut down now.</description>
</entry>
</enum>
<enumname="MAV_TYPE">
<entryvalue="0"name="MAV_TYPE_GENERIC">
<description>Generic micro air vehicle.</description>
</entry>
<entryvalue="1"name="MAV_TYPE_FIXED_WING">
<description>Fixed wing aircraft.</description>
</entry>
<entryvalue="2"name="MAV_TYPE_QUADROTOR">
<description>Quadrotor</description>
</entry>
<entryvalue="3"name="MAV_TYPE_COAXIAL">
<description>Coaxial helicopter</description>
</entry>
<entryvalue="4"name="MAV_TYPE_HELICOPTER">
<description>Normal helicopter with tail rotor.</description>
</entry>
<entryvalue="5"name="MAV_TYPE_ANTENNA_TRACKER">
<description>Ground installation</description>
</entry>
<entryvalue="6"name="MAV_TYPE_GCS">
<description>Operator control unit / ground control station</description>
<description>Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)</description>
<description>Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.</description>
<paramindex="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)</param>
<paramindex="2">Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)</param>
<paramindex="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param>
<paramindex="4">Desired yaw angle at MISSION (rotary wing)</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
</entry>
<entryvalue="17"name="MAV_CMD_NAV_LOITER_UNLIM">
<description>Loiter around this MISSION an unlimited amount of time</description>
<paramindex="1">Empty</param>
<paramindex="2">Empty</param>
<paramindex="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<paramindex="4">Desired yaw angle.</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
</entry>
<entryvalue="18"name="MAV_CMD_NAV_LOITER_TURNS">
<description>Loiter around this MISSION for X turns</description>
<paramindex="1">Turns</param>
<paramindex="2">Empty</param>
<paramindex="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<paramindex="4">Desired yaw angle.</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
</entry>
<entryvalue="19"name="MAV_CMD_NAV_LOITER_TIME">
<description>Loiter around this MISSION for X seconds</description>
<paramindex="1">Seconds (decimal)</param>
<paramindex="2">Empty</param>
<paramindex="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<description>Return to launch location</description>
<paramindex="1">Empty</param>
<paramindex="2">Empty</param>
<paramindex="3">Empty</param>
<paramindex="4">Empty</param>
<paramindex="5">Empty</param>
<paramindex="6">Empty</param>
<paramindex="7">Empty</param>
</entry>
<entryvalue="21"name="MAV_CMD_NAV_LAND">
<description>Land at location</description>
<paramindex="1">Empty</param>
<paramindex="2">Empty</param>
<paramindex="3">Empty</param>
<paramindex="4">Desired yaw angle.</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
</entry>
<entryvalue="22"name="MAV_CMD_NAV_TAKEOFF">
<description>Takeoff from ground / hand</description>
<paramindex="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<paramindex="2">Empty</param>
<paramindex="3">Empty</param>
<paramindex="4">Yaw angle (if magnetometer present), ignored without magnetometer</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
</entry>
<entryvalue="80"name="MAV_CMD_NAV_ROI">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
sensors such as cameras.</description>
<paramindex="1">Region of intereset mode. (see MAV_ROI enum)</param>
<paramindex="2">MISSION index/ target ID. (see MAV_ROI enum)</param>
<paramindex="3">ROI index (allows a vehicle to manage multiple ROI's)</param>
<paramindex="4">Empty</param>
<paramindex="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<paramindex="6">y</param>
<paramindex="7">z</param>
</entry>
<entryvalue="81"name="MAV_CMD_NAV_PATHPLANNING">
<description>Control autonomous path planning on the MAV.</description>
<paramindex="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>
<paramindex="2">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>
<paramindex="3">Empty</param>
<paramindex="4">Yaw angle at goal, in compass degrees, [0..360]</param>
<paramindex="5">Latitude/X of goal</param>
<paramindex="6">Longitude/Y of goal</param>
<paramindex="7">Altitude/Z of goal</param>
</entry>
<entryvalue="95"name="MAV_CMD_NAV_LAST">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<paramindex="1">Empty</param>
<paramindex="2">Empty</param>
<paramindex="3">Empty</param>
<paramindex="4">Empty</param>
<paramindex="5">Empty</param>
<paramindex="6">Empty</param>
<paramindex="7">Empty</param>
</entry>
<entryvalue="112"name="MAV_CMD_CONDITION_DELAY">
<description>Delay mission state machine.</description>
<paramindex="1">Delay in seconds (decimal)</param>
<description>The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.</description>
</entry>
<entryname="MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE">
<description>The X or latitude value is out of range.</description>
</entry>
<entryname="MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE">
<description>The Y or longitude value is out of range.</description>
</entry>
<entryname="MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE">
<description>The Z or altitude value is out of range.</description>
<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_CLASS ENUM</field>
<fieldtype="uint8_t"name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field>
<fieldtype="uint32_t"name="custom_mode">Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.</field>
<fieldtype="uint8_t"name="system_status">System status flag, see MAV_STATUS ENUM</field>
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<fieldtype="uint32_t"name="onboard_control_sensors_present"print_format="0x%04x">Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<fieldtype="uint32_t"name="onboard_control_sensors_enabled"print_format="0x%04x">Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<fieldtype="uint32_t"name="onboard_control_sensors_health"print_format="0x%04x">Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<fieldtype="uint16_t"name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
<fieldtype="uint16_t"name="voltage_battery">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<fieldtype="int16_t"name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
<fieldtype="uint16_t"name="drop_rate_comm">Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field>
<fieldtype="uint16_t"name="errors_comm">Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field>
<description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
<fieldtype="uint64_t"name="time_unix_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp of the component clock since boot time in milliseconds.</field>
</message>
<!-- FIXME to be removed / merged with SYSTEM_TIME -->
<messageid="4"name="PING">
<description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description>
<fieldtype="uint64_t"name="time_usec">Unix timestamp in microseconds</field>
<fieldtype="uint8_t"name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<fieldtype="uint8_t"name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
</message>
<messageid="5"name="CHANGE_OPERATOR_CONTROL">
<description>Request to control this MAV</description>
<fieldtype="uint8_t"name="target_system">System the GCS requests control for</field>
<fieldtype="uint8_t"name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<fieldtype="uint8_t"name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field>
<fieldtype="char[25]"name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field>
</message>
<messageid="6"name="CHANGE_OPERATOR_CONTROL_ACK">
<description>Accept / deny control of this MAV</description>
<fieldtype="uint8_t"name="gcs_system_id">ID of the GCS this message </field>
<fieldtype="uint8_t"name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description>
<fieldtype="char[32]"name="key">key</field>
</message>
<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>
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<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="uint16_t"name="param_count">Total number of onboard parameters</field>
<fieldtype="uint16_t"name="param_index">Index of this onboard parameter</field>
</message>
<messageid="23"name="PARAM_SET">
<description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description>
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)
</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="int32_t"name="lat">Latitude in 1E7 degrees</field>
<fieldtype="int32_t"name="lon">Longitude in 1E7 degrees</field>
<fieldtype="int32_t"name="alt">Altitude in 1E3 meters (millimeters) above MSL</field>
<fieldtype="uint16_t"name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<messageid="25"name="GPS_STATUS">
<description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible</field>
<fieldtype="int16_t"name="xgyro">Angular speed around X axis (millirad /sec)</field>
<fieldtype="int16_t"name="ygyro">Angular speed around Y axis (millirad /sec)</field>
<fieldtype="int16_t"name="zgyro">Angular speed around Z axis (millirad /sec)</field>
<fieldtype="int16_t"name="xmag">X Magnetic field (milli tesla)</field>
<fieldtype="int16_t"name="ymag">Y Magnetic field (milli tesla)</field>
<fieldtype="int16_t"name="zmag">Z Magnetic field (milli tesla)</field>
</message>
<messageid="27"name="RAW_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="int16_t"name="xgyro">Angular speed around X axis (raw)</field>
<fieldtype="int16_t"name="ygyro">Angular speed around Y axis (raw)</field>
<fieldtype="int16_t"name="zgyro">Angular speed around Z axis (raw)</field>
<fieldtype="int16_t"name="xmag">X Magnetic field (raw)</field>
<fieldtype="int16_t"name="ymag">Y Magnetic field (raw)</field>
<fieldtype="int16_t"name="zmag">Z Magnetic field (raw)</field>
</message>
<messageid="28"name="RAW_PRESSURE">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="int16_t"name="temperature">Raw Temperature measurement (raw)</field>
</message>
<messageid="29"name="SCALED_PRESSURE">
<description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="uint8_t"name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="uint8_t"name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds</field>
<fieldtype="uint8_t"name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
<description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<fieldtype="uint32_t"name="time_usec">Timestamp (since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint8_t"name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<fieldtype="uint16_t"name="servo1_raw">Servo output 1 value, in microseconds</field>
<fieldtype="uint16_t"name="servo2_raw">Servo output 2 value, in microseconds</field>
<fieldtype="uint16_t"name="servo3_raw">Servo output 3 value, in microseconds</field>
<fieldtype="uint16_t"name="servo4_raw">Servo output 4 value, in microseconds</field>
<fieldtype="uint16_t"name="servo5_raw">Servo output 5 value, in microseconds</field>
<fieldtype="uint16_t"name="servo6_raw">Servo output 6 value, in microseconds</field>
<fieldtype="uint16_t"name="servo7_raw">Servo output 7 value, in microseconds</field>
<fieldtype="uint16_t"name="servo8_raw">Servo output 8 value, in microseconds</field>
<fieldtype="int16_t"name="start_index">Start index, 0 by default</field>
<fieldtype="int16_t"name="end_index">End index, -1 by default (-1: send list to end). Else a valid index of the list</field>
</message>
<messageid="38"name="MISSION_WRITE_PARTIAL_LIST">
<description>This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!</description>
<description>Message encoding a mission item. This message is emitted to announce
the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). http://qgroundcontrol.org/mavlink/waypoint_protocol
<fieldtype="uint8_t"name="autocontinue">autocontinue to next wp</field>
<fieldtype="float"name="param1">PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters</field>
<fieldtype="float"name="param2">PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<fieldtype="float"name="param3">PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<fieldtype="float"name="param4">PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<fieldtype="float"name="x">PARAM5 / local: x position, global: latitude</field>
<fieldtype="float"name="y">PARAM6 / y position: global: longitude</field>
<fieldtype="float"name="z">PARAM7 / z position: global: altitude</field>
<description>Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol</description>
<description>Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).</description>
<description>This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.</description>
<description>A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.</description>
<fieldtype="uint16_t"name="seq">Sequence</field>
</message>
<messageid="47"name="MISSION_ACK">
<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 MISSIONs 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>
<description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/MISSION planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description>
<description>Set the current global position setpoint.</description>
<fieldtype="uint8_t"name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT</field>
<fieldtype="int32_t"name="latitude">WGS84 Latitude position in degrees * 1E7</field>
<fieldtype="int32_t"name="longitude">WGS84 Longitude position in degrees * 1E7</field>
<fieldtype="int32_t"name="altitude">WGS84 Altitude in meters * 1000 (positive for up)</field>
<fieldtype="int16_t"name="yaw">Desired yaw angle in degrees * 100</field>
</message>
<messageid="54"name="SAFETY_SET_ALLOWED_AREA">
<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="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>
<fieldtype="float"name="p2x">x position 2 / Latitude 2</field>
<fieldtype="float"name="p2y">y position 2 / Longitude 2</field>
<fieldtype="float"name="p2z">z position 2 / Altitude 2</field>
</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="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>
<fieldtype="float"name="p2x">x position 2 / Latitude 2</field>
<fieldtype="float"name="p2y">y position 2 / Longitude 2</field>
<fieldtype="float"name="p2z">z position 2 / Altitude 2</field>
</message>
<messageid="56"name="SET_ROLL_PITCH_YAW_THRUST">
<description>Set roll, pitch and yaw.</description>
<fieldtype="float"name="nav_roll">Current desired roll in degrees</field>
<fieldtype="float"name="nav_pitch">Current desired pitch in degrees</field>
<fieldtype="int16_t"name="nav_bearing">Current desired heading in degrees</field>
<fieldtype="int16_t"name="target_bearing">Bearing to current MISSION/target in degrees</field>
<fieldtype="uint16_t"name="wp_dist">Distance to active MISSION in meters</field>
<fieldtype="float"name="alt_error">Current altitude error in meters</field>
<fieldtype="float"name="aspd_error">Current airspeed error in meters/second</field>
<fieldtype="float"name="xtrack_error">Current crosstrack error on x-y plane in meters</field>
</message>
<messageid="64"name="STATE_CORRECTION">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
<fieldtype="float"name="xErr">x position error</field>
<fieldtype="float"name="yErr">y position error</field>
<fieldtype="float"name="zErr">z position error</field>
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<fieldtype="uint8_t"name="autocontinue">autocontinue to next wp</field>
<fieldtype="float"name="param1">PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters</field>
<fieldtype="float"name="param2">PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<fieldtype="float"name="param3">PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<fieldtype="float"name="param4">PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<fieldtype="float"name="x">PARAM5 / local: x position, global: latitude</field>
<fieldtype="float"name="y">PARAM6 / y position: global: longitude</field>
<fieldtype="float"name="z">PARAM7 / z position: global: altitude</field>
</message>
<messageid="81"name="MISSION_ACK">
<description>ACK / NACK for one mission element or a whole mission</description>
<fieldtype="uint8_t"name="mission_command">Command id: 0: read whole mission, 1: read mission from begin to end, 2: write mission items from begin to end, 3: clear mission.</field>
<fieldtype="uint16_t"name="begin_item"></field>
<fieldtype="uint16_t"name="end_item"></field>
</message> -->
<messageid="90"name="HIL_STATE">
<description>Sent from simulation to autopilot. This packet is useful for high throughput
applications such as hardware in the loop simulations.
</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<description>Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds</field>
<fieldtype="uint16_t"name="chan9_raw">RC channel 9 value, in microseconds</field>
<fieldtype="uint16_t"name="chan10_raw">RC channel 10 value, in microseconds</field>
<fieldtype="uint16_t"name="chan11_raw">RC channel 11 value, in microseconds</field>
<fieldtype="uint16_t"name="chan12_raw">RC channel 12 value, in microseconds</field>
<fieldtype="uint8_t"name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<messageid="100"name="OPTICAL_FLOW">
<description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description>
<!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
<messageid="249"name="MEMORY_VECT">
<description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<fieldtype="uint16_t"name="address">Starting address of the debug variables</field>
<fieldtype="uint8_t"name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field>
<fieldtype="uint8_t"name="type">Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14</field>
<fieldtype="int8_t[32]"name="value">Memory contents at specified address</field>
<description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="char[10]"name="name">Name of the debug variable</field>
<fieldtype="float"name="value">Floating point value</field>
</message>
<messageid="252"name="NAMED_VALUE_INT">
<description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="char[10]"name="name">Name of the debug variable</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, 0 = info message, 255 = critical fault</field>
<fieldtype="char[50]"name="text">Status text message, without null termination character</field>
</message>
<messageid="254"name="DEBUG">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="uint8_t"name="ind">index of debug variable</field>