diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 6fbeb12696..b800c01bea 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -985,10 +985,10 @@ Latitude (WGS84), in degrees * 1E7 Longitude (WGS84), in degrees * 1E7 Altitude (WGS84), in meters * 1000 (positive for up) - GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - GPS ground speed (m/s * 100). If unknown, set to: 65535 - Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX + GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX Number of satellites visible. If unknown, set to 255 @@ -1083,34 +1083,34 @@ Ground X Speed (Latitude), expressed as m/s * 100 Ground Y Speed (Longitude), expressed as m/s * 100 Ground Z Speed (Altitude), expressed as m/s * 100 - Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to 65535. + The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX. Timestamp (milliseconds since system boot) Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. - RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) 32767. + RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. + RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. 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. Timestamp (milliseconds since system boot) Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - RC channel 1 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 2 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 3 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 4 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 5 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 6 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 7 value, in microseconds. A value of 65535 implies the channel is unused. - RC channel 8 value, in microseconds. A value of 65535 implies the channel is unused. + RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. + RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. @@ -1315,10 +1315,10 @@ Setpoint for up to four quadrotors in a group / wing ID of the quadrotor group (0 - 255, up to 256 groups supported) ID of the flight mode (0 - 255, up to 256 modes supported) - Desired roll angle in radians +-PI (+-32767) - Desired pitch angle in radians +-PI (+-32767) - Desired yaw angle in radians, scaled to int16 +-PI (+-32767) - Collective thrust, scaled to uint16 (0..65535) + Desired roll angle in radians +-PI (+-INT16_MAX) + Desired pitch angle in radians +-PI (+-INT16_MAX) + Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) + Collective thrust, scaled to uint16 (0..UINT16_MAX) 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. @@ -1338,10 +1338,10 @@ RGB red channel (0-255) RGB green channel (0-255) RGB blue channel (0-255) - Desired roll angle in radians +-PI (+-32767) - Desired pitch angle in radians +-PI (+-32767) - Desired yaw angle in radians, scaled to int16 +-PI (+-32767) - Collective thrust, scaled to uint16 (0..65535) + Desired roll angle in radians +-PI (+-INT16_MAX) + Desired pitch angle in radians +-PI (+-INT16_MAX) + Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) + Collective thrust, scaled to uint16 (0..UINT16_MAX) Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle. @@ -1377,17 +1377,17 @@ A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - 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. + 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. System ID Component ID - RC channel 1 value, in microseconds - RC channel 2 value, in microseconds - RC channel 3 value, in microseconds - RC channel 4 value, in microseconds - RC channel 5 value, in microseconds - RC channel 6 value, in microseconds - RC channel 7 value, in microseconds - RC channel 8 value, in microseconds + RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. + RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. Metrics typically displayed on a HUD for fixed wing aircraft @@ -1446,14 +1446,14 @@ Yaw - Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations. + 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. Timestamp (microseconds since UNIX epoch or microseconds since system boot) Roll angle (rad) Pitch angle (rad) Yaw angle (rad) - Roll angular speed (rad/s) - Pitch angular speed (rad/s) - Yaw angular speed (rad/s) + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) Latitude, expressed as * 1E7 Longitude, expressed as * 1E7 Altitude in meters, expressed as * 1000 (millimeters) @@ -1499,8 +1499,8 @@ Optical flow from a flow sensor (e.g. optical mouse sensor) Timestamp (UNIX) Sensor ID - Flow in pixels in x-sensor direction - Flow in pixels in y-sensor direction + Flow in pixels * 10 in x-sensor direction (dezi-pixels) + Flow in pixels * 10 in y-sensor direction (dezi-pixels) Flow in meters in x-sensor direction, angular-speed compensated Flow in meters in y-sensor direction, angular-speed compensated Optical flow quality / confidence. 0: bad, 255: maximum quality @@ -1569,11 +1569,6 @@ The IMU readings in SI units in NED body frame Timestamp (microseconds, synced to UNIX time or since system boot) - Roll angle in inertial frame (rad) - Pitch angle in inertial frame (rad) - Yaw angle in inertial frame (rad) - Latitude, expressed as * 1E7 degrees - Longitude, expressed as * 1E7 degrees X acceleration (m/s^2) Y acceleration (m/s^2) Z acceleration (m/s^2) @@ -1586,16 +1581,19 @@ Absolute pressure in millibar Differential pressure (airspeed) in millibar Altitude calculated from pressure - GPS altitude (MSL) WGS84 Temperature in degrees celsius Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature Status of simulation environment, if used - Roll angle (rad) - Pitch angle (rad) - Yaw angle (rad) + True attitude quaternion component 1 + True attitude quaternion component 2 + True attitude quaternion component 3 + True attitude quaternion component 4 + Attitude roll expressed as Euler angles, not recommended except for human-readable outputs + Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs + Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs X acceleration m/s/s Y acceleration m/s/s Z acceleration m/s/s @@ -1603,7 +1601,13 @@ Angular speed around Y axis rad/s Angular speed around Z axis rad/s Latitude in degrees - Longitude in degrees + Longitude in degrees + Altitude in meters + Horizontal position standard deviation + Vertical position standard deviation + True velocity in m/s in NORTH direction in earth-fixed NED frame + True velocity in m/s in EAST direction in earth-fixed NED frame + True velocity in m/s in DOWN direction in earth-fixed NED frame @@ -1636,6 +1640,53 @@ Unique transfer ID 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device + + 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). + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + 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. + Latitude (WGS84), in degrees * 1E7 + Longitude (WGS84), in degrees * 1E7 + Altitude (WGS84), in meters * 1000 (positive for up) + GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 + GPS ground speed (m/s * 100). If unknown, set to: 65535 + GPS velocity in cm/s in NORTH direction in earth-fixed NED frame + GPS velocity in cm/s in EAST direction in earth-fixed NED frame + GPS velocity in cm/s in DOWN direction in earth-fixed NED frame + Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 + Number of satellites visible. If unknown, set to 255 + + + Simulated optical flow from a flow sensor (e.g. optical mouse sensor) + Timestamp (UNIX) + Sensor ID + Flow in pixels in x-sensor direction + Flow in pixels in y-sensor direction + Flow in meters in x-sensor direction, angular-speed compensated + Flow in meters in y-sensor direction, angular-speed compensated + Optical flow quality / confidence. 0: bad, 255: maximum quality + Ground distance in meters. Positive value: distance known. Negative value: Unknown distance + + + 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. + Timestamp (microseconds since UNIX epoch or microseconds since system boot) + Vehicle attitude expressed as normalized quaternion + Body frame roll / phi angular speed (rad/s) + Body frame pitch / theta angular speed (rad/s) + Body frame yaw / psi angular speed (rad/s) + Latitude, expressed as * 1E7 + Longitude, expressed as * 1E7 + Altitude in meters, expressed as * 1000 (millimeters) + Ground X Speed (Latitude), expressed as m/s * 100 + Ground Y Speed (Longitude), expressed as m/s * 100 + Ground Z Speed (Altitude), expressed as m/s * 100 + Indicated airspeed, expressed as m/s * 100 + True airspeed, expressed as m/s * 100 + X acceleration (mg) + Y acceleration (mg) + Z acceleration (mg) + Transmitte battery informations for a accu pack. Accupack ID