common_slugs.xml 17.1 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227
<?xml version="1.0"?>
<mavlink>
<messages>
   <message name="HEARTBEAT" id="0">
     <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>
     <field name="type" type="uint8_t">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
     <field name="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>
   </message>
 
   <message name="BOOT" id="1">
	<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
     <field name="version" type="uint32_t">The onboard software version</field>
   </message>

   <message name="SYSTEM_TIME" id="2">
     <description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
     <field name="time_usec" type="uint64_t">Timestamp of the master clock in microseconds since UNIX epoch.</field>
   </message>

   <message name="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>
     <field name="seq" type="uint32_t">PING sequence</field>
     <field name="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>
     <field name="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>
     <field name="time" type="uint64_t">Unix timestamp in microseconds</field>
   </message>

   <message name="ACTION" id="10">
	<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>
     <field name="target" type="uint8_t">The system executing the action</field>
     <field name="target_component" type="uint8_t">The component executing the action</field>
     <field name="action" type="uint8_t">The action id</field>
   </message>

   <message name="ACTION_ACK" id="62">
	<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>
     <field name="action" type="uint8_t">The action id</field>
     <field name="result" type="uint8_t">0: Action DENIED, 1: Action executed</field>
   </message>

   <message name="SET_MODE" id="11">
   <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>
     <field name="target" type="uint8_t">The system setting the mode</field>
     <field name="mode" type="uint8_t">The new mode</field>
   </message>

   <message name="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>
     <field name="target" type="uint8_t">The system setting the mode</field>
     <field name="nav_mode" type="uint8_t">The new navigation mode</field>
   </message>
   
   <message name="RAW_IMU" id="28">
     <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>
     <field name="usec"  type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
     <field name="xacc"  type="int16_t">X acceleration (mg raw)</field>
     <field name="yacc"  type="int16_t">Y acceleration (mg raw)</field>
     <field name="zacc"  type="int16_t">Z acceleration (mg raw)</field>
     <field name="xgyro" type="int16_t">Angular speed around X axis (adc units)</field>
     <field name="ygyro" type="int16_t">Angular speed around Y axis (adc units)</field>
     <field name="zgyro" type="int16_t">Angular speed around Z axis (adc units)</field>
     <field name="xmag"  type="int16_t">X Magnetic field (milli tesla)</field>
     <field name="ymag"  type="int16_t">Y Magnetic field (milli tesla)</field>
     <field name="zmag"  type="int16_t">Z Magnetic field (milli tesla)</field>
   </message>

  <message name="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>
     <field name="usec"  type="uint64_t">Timestamp (microseconds since UNIX epoch)</field>
     <field name="press_abs"  type="int16_t">Absolute pressure (hectopascal)</field>
     <field name="press_diff1"  type="int16_t">Differential pressure 1 (hectopascal)</field>
     <field name="press_diff2"  type="int16_t">Differential pressure 2 (hectopascal)</field>
     <field name="temperature"  type="int16_t">Raw Temperature measurement </field>
  </message>

   <message name="ATTITUDE" id="30">
    <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
     <field name="usec"  type="uint64_t">Timestamp (microseconds)</field>
     <field name="roll"  type="float">Roll angle (rad)</field>
     <field name="pitch" type="float">Pitch angle (rad)</field>
     <field name="yaw"   type="float">Yaw angle (rad)</field>
     <field name="rollspeed"  type="float">Roll angular speed (rad/s)</field>
     <field name="pitchspeed" type="float">Pitch angular speed (rad/s)</field>
     <field name="yawspeed"   type="float">Yaw angular speed (rad/s)</field>
   </message>

   <message name="LOCAL_POSITION" id="31">
     <description>The filtered local position (e.g. fused computer vision and accelerometers).</description>
     <field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
     <field name="x"   type="float">X Position</field>
     <field name="y"   type="float">Y Position</field>
     <field name="z"   type="float">Z Position</field>
     <field name="vx"  type="float">X Speed</field>
     <field name="vy"  type="float">Y Speed</field>
     <field name="vz"  type="float">Z Speed</field>
   </message>

   <message name="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>
     <field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
     <field name="fix_type" type="uint8_t">0-1: no fix, 2: 2D fix, 3: 3D fix</field>
     <field name="lat"   type="float">X Position</field>
     <field name="lon"   type="float">Y Position</field>
     <field name="alt"   type="float">Z Position in meters</field>
     <field name="eph"  type="float">Uncertainty in meters of latitude</field>
     <field name="epv"  type="float">Uncertainty in meters of longitude</field>
     <field name="v"  type="float">Overall speed</field>
     <field name="hdg"  type="float">Heading, in FIXME</field>
   </message>

   <message name="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>
     <field name="satellites_visible"   type="uint8_t">Number of satellites visible</field>
     <field name="satellite_prn"   type="array[20]">Global satellite ID</field>
     <field name="satellite_used"   type="array[20]">0: Satellite not used, 1: used for localization</field>
     <field name="satellite_elevation"   type="array[20]">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
     <field name="satellite_azimuth"  type="array[20]">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
     <field name="satellite_snr"  type="array[20]">Signal to noise ratio of satellite</field>
   </message>

   <message name="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>
     <field name="mode" type="uint8_t">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
     <field name="nav_mode" type="uint8_t">Navigation mode, see MAV_NAV_MODE ENUM</field>
     <field name="status" type="uint8_t">System status flag, see MAV_STATUS ENUM</field>
     <field name="vbat" type="uint16_t">Battery voltage, in millivolts (1 = 1 millivolt)</field>
     <field name="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>
     <field name="packet_drop" type="uint16_t">Dropped packets (packets that were corrupted on reception on the MAV)</field>
   </message>

   <message name="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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="seq" type="uint16_t">Sequence</field>
     <field name="type" type="uint8_t">0: global (GPS), 1: local, 2: global orbit, 3: local orbit</field>
     <field name="orbit" type="float">Orbit to circle around the waypoint, in meters. Set to 0 to fly straight through the waypoint</field>
     <field name="orbit_direction" type="uint8_t">Direction of the orbit circling: 0: clockwise, 1: counter-clockwise</field>
     <field name="param1" type="float">For waypoints of type 0 and 1: Radius in which the waypoint is accepted as reached, in meters</field>
     <field name="param2" type="float">For waypoints of type 0 and 1: Time that the MAV should stay inside the orbit before advancing, in milliseconds</field>
     <field name="current" type="uint8_t">false:0, true:1</field>
     <field name="x" type="float">local: x position, global: longitude</field>
     <field name="y" type="float">y position: global: latitude</field>
     <field name="z" type="float">z position: global: altitude</field>
     <field name="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
     <field name="autocontinue" type="uint8_t">autocontinue to next wp</field>
   </message>

   <message name="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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="seq" type="uint16_t">Sequence</field>
   </message>

  <message name="WAYPOINT_SET_CURRENT" id="41">
     <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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="seq" type="uint16_t">Sequence</field>
  </message>

  <message name="WAYPOINT_CURRENT" id="42">
     <description>Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.</description>
     <field name="seq" type="uint16_t">Sequence</field>
  </message>

   <message name="WAYPOINT_COUNT" id="44">
     <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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="count" type="uint16_t">Number of Waypoints in the Sequence</field>
   </message>

  <message name="WAYPOINT_CLEAR_ALL" id="45">
     <description>Delete all waypoints at once.</description>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
  </message>

   <message name="WAYPOINT_REACHED" id="46">
     <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>
     <field name="seq" type="uint16_t">Sequence</field>
   </message>

   <message name="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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="type" type="uint8_t">0: OK, 1: Error</field>
   </message>

   <message name="WAYPOINT_SET_GLOBAL_REFERENCE" id="48">
     <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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="global_x" type="float">global x position</field>
     <field name="global_y" type="float">global y position</field>
     <field name="global_z" type="float">global z position</field>
     <field name="global_yaw" type="float">global yaw orientation in radians, 0 = NORTH</field>
     <field name="local_x" type="float">local x position that matches the global x position</field>
     <field name="local_y" type="float">local y position that matches the global y position</field>
     <field name="local_z" type="float">local z position that matches the global z position</field>
     <field name="local_yaw" type="float">local yaw that matches the global yaw orientation</field>
   </message>

   
   <!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->

  <message name="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>
    <field name="severity" type="uint8_t">Severity of status, 0 = info message, 255 = critical fault</field>
    <field name="text" type="array[50]">Status text message, without null termination character</field>
  </message>


<message name="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>
     <field name="ind"  type="uint8_t">index of debug variable</field>
     <field name="value"  type="float">DEBUG value</field>
   </message>

</messages>
</mavlink>