common.xml 58.7 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 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357
<?xml version="1.0"?>
<mavlink>
<version>2</version>

<enums>
    <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.</description>
      <entry name="MAV_CMD_NAV_WAYPOINT" value="16">
        <description>Navigate to waypoint.</description>
        <param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
        <param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)</param>
        <param index="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>
        <param index="4">Desired yaw angle at waypoint (rotary wing)</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_LOITER_UNLIM" value="17">
        <description>Loiter around this waypoint an unlimited amount of time</description>
        <param index="1">Empty</param>
        <param index="2">Empty</param>
        <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
        <param index="4">Desired yaw angle.</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_LOITER_TURNS" value="18">
        <description>Loiter around this waypoint for X turns</description>
        <param index="1">Turns</param>
        <param index="2">Empty</param>
        <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
        <param index="4">Desired yaw angle.</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_LOITER_TIME" value="19">
        <description>Loiter around this waypoint for X seconds</description>
        <param index="1">Seconds (decimal)</param>
        <param index="2">Empty</param>
        <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
        <param index="4">Desired yaw angle.</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_RETURN_TO_LAUNCH" value="20">
        <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 name="MAV_CMD_NAV_LAND" value="21">
      <description>Land at location</description>
        <param index="1">Empty</param>
        <param index="2">Empty</param>
        <param index="3">Empty</param>
        <param index="4">Desired yaw angle.</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_TAKEOFF" value="22">
        <description>Takeoff from ground / hand</description>
        <param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
        <param index="2">Empty</param>
        <param index="3">Empty</param>
        <param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
        </entry>
      <entry name="MAV_CMD_NAV_ORIENTATION_TARGET" value="80">
        <description>Set the location the system should be heading towards (camera heads or
        rotary wing aircraft).</description>
        <param index="1">Empty</param>
        <param index="2">Empty</param>
        <param index="3">Empty</param>
        <param index="4">Empty</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_NAV_PATHPLANNING" value="81">
        <description>Control autonomous path planning on the MAV.</description>
        <param index="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">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">Yaw angle at goal, in compass degrees, [0..360]</param>
        <param index="5">Latitude/X of goal</param>
        <param index="6">Longitude/Y of goal</param>
        <param index="7">Altitude/Z of goal</param>
      </entry>
      <entry name="MAV_CMD_NAV_LAST" value="95">
      <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 name="MAV_CMD_CONDITION_DELAY" value="112">
      <description>Delay mission state machine.</description>
        <param index="1">Delay in seconds (decimal)</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 name="MAV_CMD_CONDITION_CHANGE_ALT" value="113">
        <description>Ascend/descend at rate.  Delay mission state machine until desired altitude reached.</description>
        <param index="1">Descent / Ascend rate (m/s)</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">Finish Altitude</param>
      </entry>
      <entry name="MAV_CMD_CONDITION_DISTANCE" value="114">
        <description>Delay mission state machine until within desired distance of next NAV point.</description>
        <param index="1">Distance (meters)</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 name="MAV_CMD_CONDITION_YAW" value="115">
        <description>Reach a certain target angle.</description>
        <param index="1">target angle: [0-360], 0 is north</param>
        <param index="2">speed during yaw change:[deg per second]</param>
        <param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param>
        <param index="4">relative offset or absolute angle: [ 1,0]</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
      <entry name="MAV_CMD_CONDITION_LAST" value="159">
      <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 name="MAV_CMD_DO_SET_MODE" value="176">
        <description>Set system mode.</description>
        <param index="1">Mode, as defined by ENUM MAV_MODE</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 name="MAV_CMD_DO_JUMP" value="177">
        <description>Jump to the desired command in the mission list.  Repeat this action only the specified number of times</description>
        <param index="1">Sequence number</param>
        <param index="2">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 name="MAV_CMD_DO_CHANGE_SPEED" value="178">
        <description>Change speed and/or throttle set points.</description>
        <param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param>
        <param index="2">Speed  (m/s, -1 indicates no change)</param>
        <param index="3">Throttle  ( Percent, -1 indicates no change)</param>
        <param index="4">Empty</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
      <entry name="MAV_CMD_DO_SET_HOME" value="179">
        <description>Changes the home location either to the current location or a specified location.</description>
        <param index="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">Empty</param>
        <param index="5">Latitude</param>
        <param index="6">Longitude</param>
        <param index="7">Altitude</param>
      </entry>
      <entry name="MAV_CMD_DO_SET_PARAMETER" value="180">
        <description>Set a system parameter.  Caution!  Use of this command requires knowledge of the numeric enumeration value of the parameter.</description>
        <param index="1">Parameter number</param>
        <param index="2">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 name="MAV_CMD_DO_SET_RELAY" value="181">
        <description>Set a relay to a condition.</description>
        <param index="1">Relay number</param>
        <param index="2">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 name="MAV_CMD_DO_REPEAT_RELAY" value="182">
        <description>Cycle a relay on and off for a desired number of cyles with a desired period.</description>
        <param index="1">Relay number</param>
        <param index="2">Cycle count</param>
        <param index="3">Cycle time (seconds, decimal)</param>
        <param index="4">Empty</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
      <entry name="MAV_CMD_DO_SET_SERVO" value="183">
        <description>Set a servo to a desired PWM value.</description>
        <param index="1">Servo number</param>
        <param index="2">PWM (microseconds, 1000 to 2000 typical)</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 name="MAV_CMD_DO_REPEAT_SERVO" value="184">
        <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">Servo number</param>
        <param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
        <param index="3">Cycle count</param>
        <param index="4">Cycle time (seconds)</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
      <entry name="MAV_CMD_DO_CONTROL_VIDEO" value="200">
        <description>Control onboard camera system.</description>
        <param index="1">Camera ID (-1 for all)</param>
        <param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
        <param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param>
        <param index="4">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 name="MAV_CMD_DO_LAST" value="240">
      <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 name="MAV_CMD_PREFLIGHT_CALIBRATION" value="241">
        <description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description>
        <param index="1">Gyro calibration: 0: no, 1: yes</param>
        <param index="2">Magnetometer calibration: 0: no, 1: yes</param>
        <param index="3">Ground pressure: 0: no, 1: yes</param>
        <param index="4">Radio calibration: 0: no, 1: yes</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
      <entry name="MAV_CMD_PREFLIGHT_STORAGE" value="245">
        <description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description>
        <param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
        <param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
        <param index="3">Reserved</param>
        <param index="4">Reserved</param>
        <param index="5">Empty</param>
        <param index="6">Empty</param>
        <param index="7">Empty</param>
      </entry>
   </enum>
   <enum name="MAV_DATA_STREAM">
     <description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
     recommendation to the autopilot software. Individual autopilots may or may not obey
     the recommended messages.
     </description>
     <entry name="MAV_DATA_STREAM_ALL" value="0"><description>Enable all data streams</description></entry>
     <entry name="MAV_DATA_STREAM_RAW_SENSORS" value="1"><description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description></entry>
     <entry name="MAV_DATA_STREAM_EXTENDED_STATUS" value="2"><description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description></entry>
     <entry name="MAV_DATA_STREAM_RC_CHANNELS" value="3"><description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description></entry>
     <entry name="MAV_DATA_STREAM_RAW_CONTROLLER" value="4"><description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description></entry>
     <entry name="MAV_DATA_STREAM_POSITION" value="6"><description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description></entry>
     <entry name="MAV_DATA_STREAM_EXTRA1" value="10"><description>Dependent on the autopilot</description></entry>
     <entry name="MAV_DATA_STREAM_EXTRA2" value="11"><description>Dependent on the autopilot</description></entry>
     <entry name="MAV_DATA_STREAM_EXTRA3" value="12"><description>Dependent on the autopilot</description></entry>
   </enum>
</enums>

<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>
     <field name="mavlink_version" type="uint8_t_mavlink_version">MAVLink version</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="SYSTEM_TIME_UTC" id="4">
    <description>UTC date and time from GPS module</description>
    <field name="utc_date" type="uint32_t">GPS UTC date ddmmyy</field>
    <field name="utc_time" type="uint32_t">GPS UTC time hhmmss</field>
  </message>
  
  <message name="CHANGE_OPERATOR_CONTROL" id="5">
    <description>Request to control this MAV</description>
    <field name="target_system" type="uint8_t">System the GCS requests control for</field>
    <field name="control_request" type="uint8_t">0: request control of this MAV, 1: Release control of this MAV</field>
    <field name="version" type="uint8_t">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>
    <field name="passkey" type="char[25]">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>
  
  <message name="CHANGE_OPERATOR_CONTROL_ACK" id="6">
    <description>Accept / deny control of this MAV</description>
    <field name="gcs_system_id" type="uint8_t">ID of the GCS this message </field>
    <field name="control_request" type="uint8_t">0: request control of this MAV, 1: Release control of this MAV</field>
    <field name="ack" type="uint8_t">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field>
  </message>
  
James Goppert's avatar
James Goppert committed
358 359 360 361 362
  <message name="AUTH_KEY" id="7">
    <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>
    <field name="key" type="char[32]">key</field>
  </message>
  
James Goppert's avatar
James Goppert committed
363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470
   <message name="ACTION_ACK" id="9">
	<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="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="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="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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="param_id" type="array[15]">Onboard parameter id</field>
     <field name="param_index" type="int16_t">Parameter index. Send -1 to use the param ID field as identifier</field>
   </message>

   <message name="PARAM_REQUEST_LIST" id="21">
     <description>Request all parameters of this component. After his request, all parameters are emitted.</description>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
   </message>

   <message name="PARAM_VALUE" id="22">
     <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>
     <field name="param_id" type="array[15]">Onboard parameter id</field>
     <field name="param_value" type="float">Onboard parameter value</field>
     <field name="param_count" type="uint16_t">Total number of onboard parameters</field>
     <field name="param_index" type="uint16_t">Index of this onboard parameter</field>
   </message>

   <message name="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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="param_id" type="array[15]">Onboard parameter id</field>
     <field name="param_value" type="float">Onboard parameter value</field>
   </message>
   
         <message name="GPS_RAW_INT" id="25">
     <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>
     <field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
     <field name="fix_type" type="uint8_t">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>
     <field name="lat"   type="int32_t">Latitude in 1E7 degrees</field>
     <field name="lon"   type="int32_t">Longitude in 1E7 degrees</field>
     <field name="alt"   type="int32_t">Altitude in 1E3 meters (millimeters)</field>
     <field name="eph"  type="float">GPS HDOP</field>
     <field name="epv"  type="float">GPS VDOP</field>
     <field name="v"  type="float">GPS ground speed (m/s)</field>
     <field name="hdg"  type="float">Compass heading in degrees, 0..360 degrees</field>
   </message>
   
   <message name="SCALED_IMU" id="26">
     <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description>
     <field name="usec"  type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
     <field name="xacc"  type="int16_t">X acceleration (mg)</field>
     <field name="yacc"  type="int16_t">Y acceleration (mg)</field>
     <field name="zacc"  type="int16_t">Z acceleration (mg)</field>
     <field name="xgyro" type="int16_t">Angular speed around X axis (millirad /sec)</field>
     <field name="ygyro" type="int16_t">Angular speed around Y axis (millirad /sec)</field>
     <field name="zgyro" type="int16_t">Angular speed around Z axis (millirad /sec)</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="GPS_STATUS" id="27">
     <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>
     <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="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 or microseconds since system boot)</field>
     <field name="xacc"  type="int16_t">X acceleration (raw)</field>
     <field name="yacc"  type="int16_t">Y acceleration (raw)</field>
     <field name="zacc"  type="int16_t">Z acceleration (raw)</field>
     <field name="xgyro" type="int16_t">Angular speed around X axis (raw)</field>
     <field name="ygyro" type="int16_t">Angular speed around Y axis (raw)</field>
     <field name="zgyro" type="int16_t">Angular speed around Z axis (raw)</field>
     <field name="xmag"  type="int16_t">X Magnetic field (raw)</field>
     <field name="ymag"  type="int16_t">Y Magnetic field (raw)</field>
     <field name="zmag"  type="int16_t">Z Magnetic field (raw)</field>
   </message>

  <message name="RAW_PRESSURE" id="29">
James Goppert's avatar
James Goppert committed
471 472 473 474 475 476 477 478 479 480
     <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 or microseconds since system boot)</field>
     <field name="press_abs"    type="int16_t">Absolute pressure (raw)</field>
     <field name="press_diff1"  type="int16_t">Differential pressure 1 (raw)</field>
     <field name="press_diff2"  type="int16_t">Differential pressure 2 (raw)</field>
     <field name="temperature"  type="int16_t">Raw Temperature measurement (raw)</field>
   </message>

  <message name="SCALED_PRESSURE" id="38">
     <description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
James Goppert's avatar
James Goppert committed
481 482
     <field name="usec"  type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
     <field name="press_abs"  type="float">Absolute pressure (hectopascal)</field>
James Goppert's avatar
James Goppert committed
483 484
     <field name="press_diff"  type="float">Differential pressure 1 (hectopascal)</field>
     <field name="temperature"  type="int16_t">Temperature measurement (0.01 degrees celsius)</field>
James Goppert's avatar
James Goppert committed
485 486
   </message>

James Goppert's avatar
James Goppert committed
487

James Goppert's avatar
James Goppert committed
488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509
   <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 since UNIX epoch or microseconds since system boot)</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). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description>
     <field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</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>
   
James Goppert's avatar
James Goppert committed
510

James Goppert's avatar
James Goppert committed
511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657
   <message name="GLOBAL_POSITION" id="33">
     <description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
     <field name="usec" type="uint64_t">Timestamp (microseconds since unix epoch)</field>
     <field name="lat"   type="float">Latitude, in degrees</field>
     <field name="lon"   type="float">Longitude, in degrees</field>
     <field name="alt"   type="float">Absolute altitude, in meters</field>
     <field name="vx"  type="float">X Speed (in Latitude direction, positive: going north)</field>
     <field name="vy"  type="float">Y Speed (in Longitude direction, positive: going east)</field>
     <field name="vz"  type="float">Z Speed (in Altitude direction, positive: going up)</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. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
     <field name="usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
     <field name="fix_type" type="uint8_t">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>
     <field name="lat"   type="float">Latitude in degrees</field>
     <field name="lon"   type="float">Longitude in degrees</field>
     <field name="alt"   type="float">Altitude in meters</field>
     <field name="eph"  type="float">GPS HDOP</field>
     <field name="epv"  type="float">GPS VDOP</field>
     <field name="v"  type="float">GPS ground speed</field>
     <field name="hdg"  type="float">Compass heading in degrees, 0..360 degrees</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="load" type="uint16_t">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
     <field name="vbat" type="uint16_t">Battery voltage, in millivolts (1 = 1 millivolt)</field>
     <field name="battery_remaining" type="uint16_t">Remaining battery energy: (0%: 0, 100%: 1000)</field>
     <field name="packet_drop" type="uint16_t">Dropped packets (packets that were corrupted on reception on the MAV)</field>
   </message>

   <message name="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>
     <field name="chan1_raw" type="uint16_t">RC channel 1 value, in microseconds</field>
     <field name="chan2_raw" type="uint16_t">RC channel 2 value, in microseconds</field>
     <field name="chan3_raw" type="uint16_t">RC channel 3 value, in microseconds</field>
     <field name="chan4_raw" type="uint16_t">RC channel 4 value, in microseconds</field>
     <field name="chan5_raw" type="uint16_t">RC channel 5 value, in microseconds</field>
     <field name="chan6_raw" type="uint16_t">RC channel 6 value, in microseconds</field>
     <field name="chan7_raw" type="uint16_t">RC channel 7 value, in microseconds</field>
     <field name="chan8_raw" type="uint16_t">RC channel 8 value, in microseconds</field>
     <field name="rssi" type="uint8_t">Receive signal strength indicator, 0: 0%, 255: 100%</field>
   </message>

   <message name="RC_CHANNELS_SCALED" id="36">
     <description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description>
     <field name="chan1_scaled" type="int16_t">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan2_scaled" type="int16_t">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan3_scaled" type="int16_t">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan4_scaled" type="int16_t">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan5_scaled" type="int16_t">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan6_scaled" type="int16_t">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan7_scaled" type="int16_t">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="chan8_scaled" type="int16_t">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
     <field name="rssi" type="uint8_t">Receive signal strength indicator, 0: 0%, 255: 100%</field>
   </message>
   
     <message name="SERVO_OUTPUT_RAW" id="37">
    <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>
    <field name="servo1_raw" type="uint16_t">Servo output 1 value, in microseconds</field>
    <field name="servo2_raw" type="uint16_t">Servo output 2 value, in microseconds</field>
    <field name="servo3_raw" type="uint16_t">Servo output 3 value, in microseconds</field>
    <field name="servo4_raw" type="uint16_t">Servo output 4 value, in microseconds</field>
    <field name="servo5_raw" type="uint16_t">Servo output 5 value, in microseconds</field>
    <field name="servo6_raw" type="uint16_t">Servo output 6 value, in microseconds</field>
    <field name="servo7_raw" type="uint16_t">Servo output 7 value, in microseconds</field>
    <field name="servo8_raw" type="uint16_t">Servo output 8 value, in microseconds</field>
  </message> 

   <message name="WAYPOINT" id="39">
     <description>Message encoding a waypoint. This message is emitted to announce
     the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed</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="frame" type="uint8_t">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field>
     <field name="command" type="uint8_t">The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs</field>
     <field name="current" type="uint8_t">false:0, true:1</field>
     <field name="autocontinue" type="uint8_t">autocontinue to next wp</field>
     <field name="param1" type="float">PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters</field>
     <field name="param2" type="float">PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
     <field name="param3" type="float">PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
     <field name="param4" type="float">PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
     <field name="x" type="float">PARAM5 / local: x position, global: latitude</field>
     <field name="y" type="float">PARAM6 / y position: global: longitude</field>
     <field name="z" type="float">PARAM7 / z position: global: altitude</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_REQUEST_LIST" id="43">
     <description>Request the overall list of waypoints from the system/component.</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_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="GPS_SET_GLOBAL_ORIGIN" 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>
James Goppert's avatar
James Goppert committed
658 659 660
     <field name="latitude" type="int32_t">global position * 1E7</field>
     <field name="longitude" type="int32_t">global position * 1E7</field>
     <field name="altitude" type="int32_t">global position * 1000</field>
James Goppert's avatar
James Goppert committed
661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876
   </message>
   
   <message name="GPS_LOCAL_ORIGIN_SET" id="49">
    <description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description>
    <field name="latitude" type="int32_t">Latitude (WGS84), expressed as * 1E7</field>
    <field name="longitude" type="int32_t">Longitude (WGS84), expressed as * 1E7</field>
    <field name="altitude" type="int32_t">Altitude(WGS84), expressed as * 1000</field>
  </message>

   <message name="LOCAL_POSITION_SETPOINT_SET" id="50">
     <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>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</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="yaw" type="float">Desired yaw angle</field>
   </message>

   <message name="LOCAL_POSITION_SETPOINT" id="51">
     <description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
     <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="yaw" type="float">Desired yaw angle</field>
   </message>
   
   <message name="CONTROL_STATUS" id="52">
     <field name="position_fix" type="uint8_t">Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix </field>
     <field name="vision_fix" type="uint8_t">Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix </field>
     <field name="gps_fix" type="uint8_t">GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix </field>
     <field name="ahrs_health" type="uint8_t">Attitude estimation health: 0: poor, 255: excellent</field>
     <field name="control_att" type="uint8_t">0: Attitude control disabled, 1: enabled</field>
     <field name="control_pos_xy" type="uint8_t">0: X, Y position control disabled, 1: enabled</field>
     <field name="control_pos_z" type="uint8_t">0: Z position control disabled, 1: enabled</field>
     <field name="control_pos_yaw" type="uint8_t">0: Yaw angle control disabled, 1: enabled</field>
   </message>
   
      <message name="SAFETY_SET_ALLOWED_AREA" id="53">
     <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/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description>
     <field name="target_system" type="uint8_t">System ID</field>
     <field name="target_component" type="uint8_t">Component ID</field>
     <field name="frame" type="uint8_t">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>
     <field name="p1x" type="float">x position 1 / Latitude 1</field>
     <field name="p1y" type="float">y position 1 / Longitude 1</field>
     <field name="p1z" type="float">z position 1 / Altitude 1</field>
     <field name="p2x" type="float">x position 2 / Latitude 2</field>
     <field name="p2y" type="float">y position 2 / Longitude 2</field>
     <field name="p2z" type="float">z position 2 / Altitude 2</field>
   </message>
   
   <message name="SAFETY_ALLOWED_AREA" id="54">
     <description>Read out the safety zone the MAV currently assumes.</description>
     <field name="frame" type="uint8_t">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>
     <field name="p1x" type="float">x position 1 / Latitude 1</field>
     <field name="p1y" type="float">y position 1 / Longitude 1</field>
     <field name="p1z" type="float">z position 1 / Altitude 1</field>
     <field name="p2x" type="float">x position 2 / Latitude 2</field>
     <field name="p2y" type="float">y position 2 / Longitude 2</field>
     <field name="p2z" type="float">z position 2 / Altitude 2</field>
   </message>

   <message name="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>
     <field name="enabled" type="uint8_t">1: enabled, 0: disabled</field>
     <field name="roll" type="int8_t">Attitude roll: -128: -100%, 127: +100%</field>
     <field name="pitch" type="int8_t">Attitude pitch: -128: -100%, 127: +100%</field>
     <field name="yaw" type="int8_t">Attitude yaw: -128: -100%, 127: +100%</field>
     <field name="thrust" type="int8_t">Attitude thrust: -128: -100%, 127: +100%</field>
   </message>

   <message name="POSITION_CONTROLLER_OUTPUT" id="61">
     <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>
     <field name="enabled" type="uint8_t">1: enabled, 0: disabled</field>
     <field name="x" type="int8_t">Position x: -128: -100%, 127: +100%</field>
     <field name="y" type="int8_t">Position y: -128: -100%, 127: +100%</field>
     <field name="z" type="int8_t">Position z: -128: -100%, 127: +100%</field>
     <field name="yaw" type="int8_t">Position yaw: -128: -100%, 127: +100%</field>
   </message>
   
      <message name="NAV_CONTROLLER_OUTPUT" id="62">
     <description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs
of the controller before actual flight and to assist with tuning controller parameters </description>
     <field name="nav_roll" type="float">Current desired roll in degrees</field>
     <field name="nav_pitch" type="float">Current desired pitch in degrees</field>
     <field name="nav_bearing" type="int16_t">Current desired heading in degrees</field>
     <field name="target_bearing" type="int16_t">Bearing to current waypoint/target in degrees</field>
     <field name="wp_dist" type="uint16_t">Distance to active waypoint in meters</field>
     <field name="alt_error" type="float">Current altitude error in meters</field>
     <field name="aspd_error" type="float">Current airspeed error in meters/second</field>
     <field name="xtrack_error" type="float">Current crosstrack error on x-y plane in meters</field>
   </message> 
   
   <message name="POSITION_TARGET" id="63">
   <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>
     <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="yaw" type="float">yaw orientation in radians, 0 = NORTH</field>
   </message>
   
   <message name="STATE_CORRECTION" id="64">
   <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>
     <field name="xErr" type="float">x position error</field>
     <field name="yErr" type="float">y position error</field>
     <field name="zErr" type="float">z position error</field>
     <field name="rollErr" type="float">roll error (radians)</field>
     <field name="pitchErr" type="float">pitch error (radians)</field>
     <field name="yawErr" type="float">yaw error (radians)</field>
     <field name="vxErr" type="float">x velocity</field>
     <field name="vyErr" type="float">y velocity</field>
     <field name="vzErr" type="float">z velocity</field>
   </message>

   <message name="SET_ALTITUDE" id="65">
     <field name="target" type="uint8_t">The system setting the altitude</field>
     <field name="mode" type="uint32_t">The new altitude in meters</field>
   </message>

  <message name="REQUEST_DATA_STREAM" id="66">
     <field name="target_system" type="uint8_t">The target requested to send the message stream.</field>
     <field name="target_component" type="uint8_t">The target requested to send the message stream.</field>
     <field name="req_stream_id" type="uint8_t">The ID of the requested message type</field>
     <field name="req_message_rate" type="uint16_t">The requested interval between two messages of this type</field>
     <field name="start_stop" type="uint8_t">1 to start sending, 0 to stop sending.</field>
   </message>

   <message name="MANUAL_CONTROL" id="69">
     <field name="target" type="uint8_t">The system to be controlled</field>
     <field name="roll" type="float">roll</field>
     <field name="pitch" type="float">pitch</field>
     <field name="yaw" type="float">yaw</field>
     <field name="thrust" type="float">thrust</field>
     <field name="roll_manual" type="uint8_t">roll control enabled auto:0, manual:1</field>
     <field name="pitch_manual" type="uint8_t">pitch auto:0, manual:1</field>
     <field name="yaw_manual" type="uint8_t">yaw auto:0, manual:1</field>
     <field name="thrust_manual" type="uint8_t">thrust auto:0, manual:1</field>
   </message>

   <message name="GLOBAL_POSITION_INT" id="73">
     <description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description>
     <field name="lat"   type="int32_t">Latitude, expressed as * 1E7</field>
     <field name="lon"   type="int32_t">Longitude, expressed as * 1E7</field>
     <field name="alt"   type="int32_t">Altitude in meters, expressed as * 1000 (millimeters)</field>
     <field name="vx"  type="int16_t">Ground X Speed (Latitude), expressed as m/s * 100</field>
     <field name="vy"  type="int16_t">Ground Y Speed (Longitude), expressed as m/s * 100</field>
     <field name="vz"  type="int16_t">Ground Z Speed (Altitude), expressed as m/s * 100</field>
   </message>

  <message name="VFR_HUD" id="74">
     <description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
     <field name="airspeed" type="float">Current airspeed in m/s</field>
     <field name="groundspeed" type="float">Current ground speed in m/s</field>
     <field name="heading" type="int16_t">Current heading in degrees, in compass units (0..360, 0=north)</field>
     <field name="throttle" type="uint16_t">Current throttle setting in integer percent, 0 to 100</field>
     <field name="alt" type="float">Current altitude (MSL), in meters</field>
     <field name="climb" type="float">Current climb rate in meters/second</field>
   </message> 
   
   <message name="COMMAND" id="75">
     <description>Send a command with up to four parameters to the MAV</description>
     <field name="target_system" type="uint8_t">System which should execute the command</field>
     <field name="target_component" type="uint8_t">Component which should execute the command, 0 for all components</field>
     <field name="command" type="uint8_t">Command ID, as defined by MAV_CMD enum.</field>
     <field name="confirmation" type="uint8_t">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field>
     <field name="param1" type="float">Parameter 1, as defined by MAV_CMD enum.</field>
     <field name="param2" type="float">Parameter 2, as defined by MAV_CMD enum.</field>
     <field name="param3" type="float">Parameter 3, as defined by MAV_CMD enum.</field>
     <field name="param4" type="float">Parameter 4, as defined by MAV_CMD enum.</field>
   </message>
   
   <message name="COMMAND_ACK" id="76">
     <description>Report status of a command. Includes feedback wether the command was executed</description>
     <field name="command" type="float">Current airspeed in m/s</field>
     <field name="result" type="float">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
   </message>
   
   <!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->




  <message name="DEBUG_VECT" id="251">
     <field name="name" type="char[10]">Name</field>
     <field name="usec" type="uint64_t">Timestamp</field>
     <field name="x" type="float">x</field>
     <field name="y" type="float">y</field>
     <field name="z" type="float">z</field>
   </message>

<message name="NAMED_VALUE_FLOAT" id="252">
     <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>
     <field name="name"  type="char[10]">Name of the debug variable</field>
     <field name="value"  type="float">Floating point value</field>
   </message>

<message name="NAMED_VALUE_INT" id="253">
     <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>
     <field name="name"  type="char[10]">Name of the debug variable</field>
     <field name="value"  type="int32_t">Signed integer value</field>
   </message>

  <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="int8_t[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>