diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 75eb209d16..3e2e136de7 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -905,10 +905,10 @@ Mission command to control a camera or antenna mount, using a quaternion as reference. - q1 - quaternion param #1 - q2 - quaternion param #2 - q3 - quaternion param #3 - q4 - quaternion param #4 + q1 - quaternion param #1, w (1 in null-rotation) + q2 - quaternion param #2, x (0 in null-rotation) + q3 - quaternion param #3, y (0 in null-rotation) + q4 - quaternion param #4, z (0 in null-rotation) Empty Empty Empty @@ -1450,10 +1450,10 @@ The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Timestamp (milliseconds since system boot) - Quaternion component 1 - Quaternion component 2 - Quaternion component 3 - Quaternion component 4 + Quaternion component 1, w (1 in null-rotation) + Quaternion component 2, x (0 in null-rotation) + Quaternion component 3, y (0 in null-rotation) + Quaternion component 4, z (0 in null-rotation) Roll angular speed (rad/s) Pitch angular speed (rad/s) Yaw angular speed (rad/s) @@ -2052,10 +2052,10 @@ Status of simulation environment, if used - True attitude quaternion component 1 - True attitude quaternion component 2 - True attitude quaternion component 3 - True attitude quaternion component 4 + True attitude quaternion component 1, w (1 in null-rotation) + True attitude quaternion component 2, x (0 in null-rotation) + True attitude quaternion component 3, y (0 in null-rotation) + True attitude quaternion component 4, z (0 in null-rotation) 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 @@ -2136,7 +2136,7 @@ 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 + Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation) Body frame roll / phi angular speed (rad/s) Body frame pitch / theta angular speed (rad/s) Body frame yaw / psi angular speed (rad/s) @@ -2322,7 +2322,8 @@ Latitude (degrees *10^7) Longitude (degrees *10^7) grid spacing (zero if terrain at this location unavailable) - Terrain height in meters AMSL (-32767 if unavailable) + Terrain height in meters AMSL + Current vehicle height above lat/lon terrain height (meters) Number of 4x4 terrain blocks waiting to be received or read from disk Number of 4x4 terrain blocks in memory