<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>
<fieldname="type"type="uint8_t">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<fieldname="autopilot"type="uint8_t">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
<description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
<fieldname="time_usec"type="uint64_t">Timestamp of the master clock in microseconds since UNIX epoch.</field>
</message>
<messagename="PING"id="3">
<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>
<fieldname="target_system"type="uint8_t">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>
<fieldname="target_component"type="uint8_t">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>
<fieldname="time"type="uint64_t">Unix timestamp in microseconds</field>
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<fieldname="target"type="uint8_t">The system setting the mode</field>
<fieldname="mode"type="uint8_t">The new mode</field>
</message>
<messagename="SET_NAV_MODE"id="12">
<description>Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components.</description>
<fieldname="target"type="uint8_t">The system setting the mode</field>
<fieldname="nav_mode"type="uint8_t">The new navigation mode</field>
</message>
<messagename="PARAM_REQUEST_READ"id="20">
<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>
<fieldname="param_count"type="uint16_t">Total number of onboard parameters</field>
<fieldname="param_index"type="uint16_t">Index of this onboard parameter</field>
</message>
<messagename="PARAM_SET"id="23">
<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 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>
<fieldname="usec"type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<fieldname="xmag"type="int16_t">X Magnetic field (milli tesla)</field>
<fieldname="ymag"type="int16_t">Y Magnetic field (milli tesla)</field>
<fieldname="zmag"type="int16_t">Z Magnetic field (milli tesla)</field>
</message>
<messagename="RAW_PRESSURE"id="29">
<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>
<fieldname="usec"type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
<description>The filtered local position (e.g. fused computer vision and accelerometers).</description>
<fieldname="usec"type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<fieldname="x"type="float">X Position</field>
<fieldname="y"type="float">Y Position</field>
<fieldname="z"type="float">Z Position</field>
<fieldname="vx"type="float">X Speed</field>
<fieldname="vy"type="float">Y Speed</field>
<fieldname="vz"type="float">Z Speed</field>
</message>
<messagename="GPS_RAW"id="32">
<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.</description>
<fieldname="usec"type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<fieldname="fix_type"type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
<fieldname="lat"type="float">X Position</field>
<fieldname="lon"type="float">Y Position</field>
<fieldname="alt"type="float">Z Position in meters</field>
<fieldname="eph"type="float">Uncertainty in meters of latitude</field>
<fieldname="epv"type="float">Uncertainty in meters of longitude</field>
<fieldname="v"type="float">Overall speed</field>
<fieldname="hdg"type="float">Heading, in FIXME</field>
</message>
<messagename="GPS_STATUS"id="27">
<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. This message can contain information for up to 20 satellites.</description>
<fieldname="satellites_visible"type="uint8_t">Number of satellites visible</field>
<fieldname="satellite_used"type="array[20]">0: Satellite not used, 1: used for localization</field>
<fieldname="satellite_elevation"type="array[20]">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
<fieldname="satellite_azimuth"type="array[20]">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
<fieldname="satellite_snr"type="array[20]">Signal to noise ratio of satellite</field>
</message>
<messagename="GLOBAL_POSITION"id="33">
<description>The filtered global position (e.g. fused GPS and accelerometers).</description>
<fieldname="usec"type="uint64_t">Timestamp (microseconds since unix epoch)</field>
<fieldname="lat"type="float">X Position</field>
<fieldname="lon"type="float">Y Position</field>
<fieldname="alt"type="float">Z Position</field>
<fieldname="vx"type="float">X Speed</field>
<fieldname="vy"type="float">Y Speed</field>
<fieldname="vz"type="float">Z Speed</field>
</message>
<messagename="SYS_STATUS"id="34">
<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>
<fieldname="mode"type="uint8_t">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
<fieldname="nav_mode"type="uint8_t">Navigation mode, see MAV_NAV_MODE ENUM</field>
<fieldname="status"type="uint8_t">System status flag, see MAV_STATUS ENUM</field>
<fieldname="load"type="uint16_t">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
<fieldname="vbat"type="uint16_t">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<fieldname="motor_block"type="uint8_t">Motor block status flag, 0: Motors can be switched on (and could be either off or on), 1: Mechanical motor block switch is on, motors cannot be switched on (and are definitely off)</field>
<fieldname="packet_drop"type="uint16_t">Dropped packets (packets that were corrupted on reception on the MAV)</field>
</message>
<messagename="RC_CHANNELS_RAW"id="35">
<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>
<fieldname="chan1_raw"type="uint16_t">RC channel 1 value, in microseconds</field>
<fieldname="chan2_raw"type="uint16_t">RC channel 2 value, in microseconds</field>
<fieldname="chan3_raw"type="uint16_t">RC channel 3 value, in microseconds</field>
<fieldname="chan4_raw"type="uint16_t">RC channel 4 value, in microseconds</field>
<fieldname="chan5_raw"type="uint16_t">RC channel 5 value, in microseconds</field>
<fieldname="chan6_raw"type="uint16_t">RC channel 6 value, in microseconds</field>
<fieldname="chan7_raw"type="uint16_t">RC channel 7 value, in microseconds</field>
<fieldname="chan8_raw"type="uint16_t">RC channel 8 value, in microseconds</field>
<fieldname="rssi"type="uint8_t">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<messagename="RC_CHANNELS_SCALED"id="36">
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description>
<fieldname="rssi"type="uint8_t">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<messagename="WAYPOINT"id="39">
<description>Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint. It cannot be used to set a waypoint, use WAYPOINT_SET for this purpose. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon. The global and body frame are related as: positive Z-down, positive X(front looking north, positive Y(body:right) looking east. Therefore y encodes in global mode the latitude, whereas x encodes the longitude and z the GPS altitude (WGS84).</description>
<fieldname="frame"type="uint8_t">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field>
<fieldname="action"type="uint8_t">The scheduled action for the waypoint. see MAV_ACTION in mavlink_types.h</field>
<fieldname="orbit"type="float">Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint</field>
<fieldname="orbit_direction"type="uint8_t">Direction of the orbit circling: 0: clockwise, 1: counter-clockwise</field>
<fieldname="param1"type="float">For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters</field>
<fieldname="param2"type="float">For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds</field>
<fieldname="yaw"type="float">yaw orientation in radians, 0 = NORTH</field>
<fieldname="autocontinue"type="uint8_t">autocontinue to next wp</field>
</message>
<messagename="WAYPOINT_REQUEST"id="40">
<description>Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.</description>
<description>Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).</description>
<description>This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.</description>
<description>A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.</description>
<fieldname="seq"type="uint16_t">Sequence</field>
</message>
<messagename="WAYPOINT_ACK"id="47">
<description>Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description>
<description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<fieldname="global_x"type="float">global x position</field>
<fieldname="global_y"type="float">global y position</field>
<fieldname="global_z"type="float">global z position</field>
<fieldname="global_yaw"type="float">global yaw orientation in radians, 0 = NORTH</field>
<fieldname="local_x"type="float">local x position that matches the global x position</field>
<fieldname="local_y"type="float">local y position that matches the global y position</field>
<fieldname="local_z"type="float">local z position that matches the global z position</field>
<fieldname="local_yaw"type="float">local yaw that matches the global yaw orientation</field>
</message>
<!--
<messagename="SAFETY_SET_ALLOWED_AREA"id="49">
Set a safety zone, which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.
<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/waypoint 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>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
<fieldname="x"type="float">x position 1</field>
<fieldname="y"type="float">y position 1</field>
<fieldname="z"type="float">z position 1</field>
<fieldname="yaw"type="float">x position 2</field>
</message>
<messagename="ATTITUDE_CONTROLLER_OUTPUT"id="60">
<description>The output of the attitude controller. This output is the control response the controller currently generates and the attitude the MAV would take if it is under control of the attitude controller. The primary use of this message is to check the response and signs of the controller before the actual flight.</description>
<description>The output of the position controller. The primary use of this message is to check the response and signs of the controller before the actual flight.</description>
<description>The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint.</description>
<fieldname="x"type="float">x position</field>
<fieldname="y"type="float">y position</field>
<fieldname="z"type="float">z position</field>
<fieldname="yaw"type="float">yaw orientation in radians, 0 = NORTH</field>
<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>
<fieldname="xErr"type="float">x position error</field>
<fieldname="yErr"type="float">y position error</field>
<fieldname="zErr"type="float">z position error</field>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
<messagename="STATUSTEXT"id="254">
<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>
<fieldname="severity"type="uint8_t">Severity of status, 0 = info message, 255 = critical fault</field>
<fieldname="text"type="array[50]">Status text message, without null termination character</field>
</message>
<messagename="DEBUG"id="255">
<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>
<fieldname="ind"type="uint8_t">index of debug variable</field>