<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
<fieldtype="uint16_t"name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX</field>
<fieldtype="uint16_t"name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX</field>
<fieldtype="uint16_t"name="vel">GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX</field>
<fieldtype="uint16_t"name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX</field>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<messageid="25"name="GPS_STATUS">
@ -1083,34 +1083,34 @@
@@ -1083,34 +1083,34 @@
<fieldtype="int16_t"name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<fieldtype="int16_t"name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<fieldtype="int16_t"name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<fieldtype="uint16_t"name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX</field>
</message>
<messageid="34"name="RC_CHANNELS_SCALED">
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to 65535.</description>
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="uint8_t"name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.</field>
<fieldtype="uint8_t"name="rssi">Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.</field>
</message>
<messageid="35"name="RC_CHANNELS_RAW">
<description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<fieldtype="uint32_t"name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<fieldtype="uint8_t"name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.</field>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.</field>
<fieldtype="uint8_t"name="rssi">Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.</field>
</message>
<messageid="36"name="SERVO_OUTPUT_RAW">
@ -1315,10 +1315,10 @@
@@ -1315,10 +1315,10 @@
<description>Setpoint for up to four quadrotors in a group / wing</description>
<fieldtype="uint8_t"name="group">ID of the quadrotor group (0 - 255, up to 256 groups supported)</field>
<fieldtype="uint8_t"name="mode">ID of the flight mode (0 - 255, up to 256 modes supported)</field>
<fieldtype="int16_t[4]"name="roll">Desired roll angle in radians +-PI (+-32767)</field>
<fieldtype="int16_t[4]"name="pitch">Desired pitch angle in radians +-PI (+-32767)</field>
<fieldtype="int16_t[4]"name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-32767)</field>
<fieldtype="uint16_t[4]"name="thrust">Collective thrust, scaled to uint16 (0..65535)</field>
<fieldtype="int16_t[4]"name="roll">Desired roll angle in radians +-PI (+-INT16_MAX)</field>
<fieldtype="int16_t[4]"name="pitch">Desired pitch angle in radians +-PI (+-INT16_MAX)</field>
<fieldtype="int16_t[4]"name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)</field>
<fieldtype="uint16_t[4]"name="thrust">Collective thrust, scaled to uint16 (0..UINT16_MAX)</field>
</message>
<messageid="62"name="NAV_CONTROLLER_OUTPUT">
<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>
@ -1338,10 +1338,10 @@
@@ -1338,10 +1338,10 @@
<fieldtype="uint8_t[4]"name="led_red">RGB red channel (0-255)</field>
<fieldtype="uint8_t[4]"name="led_blue">RGB green channel (0-255)</field>
<fieldtype="uint8_t[4]"name="led_green">RGB blue channel (0-255)</field>
<fieldtype="int16_t[4]"name="roll">Desired roll angle in radians +-PI (+-32767)</field>
<fieldtype="int16_t[4]"name="pitch">Desired pitch angle in radians +-PI (+-32767)</field>
<fieldtype="int16_t[4]"name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-32767)</field>
<fieldtype="uint16_t[4]"name="thrust">Collective thrust, scaled to uint16 (0..65535)</field>
<fieldtype="int16_t[4]"name="roll">Desired roll angle in radians +-PI (+-INT16_MAX)</field>
<fieldtype="int16_t[4]"name="pitch">Desired pitch angle in radians +-PI (+-INT16_MAX)</field>
<fieldtype="int16_t[4]"name="yaw">Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX)</field>
<fieldtype="uint16_t[4]"name="thrust">Collective thrust, scaled to uint16 (0..UINT16_MAX)</field>
</message>
<messageid="64"name="STATE_CORRECTION">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
@ -1377,17 +1377,17 @@
@@ -1377,17 +1377,17 @@
<fieldtype="uint16_t"name="buttons">A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.</field>
</message>
<messageid="70"name="RC_CHANNELS_OVERRIDE">
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds</field>
<fieldtype="uint16_t"name="chan1_raw">RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan2_raw">RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan3_raw">RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan4_raw">RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan5_raw">RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan6_raw">RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan7_raw">RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<fieldtype="uint16_t"name="chan8_raw">RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
</message>
<messageid="74"name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
@ -1446,14 +1446,14 @@
@@ -1446,14 +1446,14 @@
<fieldtype="float"name="yaw">Yaw</field>
</message>
<messageid="90"name="HIL_STATE">
<description>Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>
<description>DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="float"name="ygyro">Angular speed around Y axis rad/s</field>
<fieldtype="float"name="zgyro">Angular speed around Z axis rad/s</field>
<fieldtype="float"name="lat">Latitude in degrees</field>
<fieldtype="float"name="lng">Longitude in degrees</field>
<fieldtype="float"name="lon">Longitude in degrees</field>
<fieldtype="float"name="alt">Altitude in meters</field>
<fieldtype="float"name="std_dev_horz">Horizontal position standard deviation</field>
<fieldtype="float"name="std_dev_vert">Vertical position standard deviation</field>
<fieldtype="float"name="vn">True velocity in m/s in NORTH direction in earth-fixed NED frame</field>
<fieldtype="float"name="ve">True velocity in m/s in EAST direction in earth-fixed NED frame</field>
<fieldtype="float"name="vd">True velocity in m/s in DOWN direction in earth-fixed NED frame</field>
</message>
<messagename="RADIO_STATUS"id="109">
@ -1636,6 +1640,53 @@
@@ -1636,6 +1640,53 @@
<fieldtype="uint64_t"name="transfer_uid">Unique transfer ID</field>
<fieldtype="uint8_t"name="result">0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device</field>
</message>
<messageid="113"name="HIL_GPS">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="uint8_t"name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<fieldtype="int32_t"name="lat">Latitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="lon">Longitude (WGS84), in degrees * 1E7</field>
<fieldtype="int32_t"name="alt">Altitude (WGS84), in meters * 1000 (positive for up)</field>
<fieldtype="uint16_t"name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<fieldtype="uint16_t"name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<fieldtype="int16_t"name="vn">GPS velocity in cm/s in NORTH direction in earth-fixed NED frame</field>
<fieldtype="int16_t"name="ve">GPS velocity in cm/s in EAST direction in earth-fixed NED frame</field>
<fieldtype="int16_t"name="vd">GPS velocity in cm/s in DOWN direction in earth-fixed NED frame</field>
<fieldtype="uint16_t"name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<fieldtype="uint8_t"name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<messageid="114"name="HIL_OPTICAL_FLOW">
<description>Simulated optical flow from a flow sensor (e.g. optical mouse sensor)</description>
<description>Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>
<fieldtype="uint64_t"name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<fieldtype="float[4]"name="attitude_quaternion">Vehicle attitude expressed as normalized quaternion</field>
<fieldtype="float"name="rollspeed">Body frame roll / phi angular speed (rad/s)</field>