<fieldtype="float"name="q1">True attitude quaternion component 1, w (1 in null-rotation)</field>
<fieldtype="float"name="q2">True attitude quaternion component 2, x (0 in null-rotation)</field>
<fieldtype="float"name="q3">True attitude quaternion component 3, y (0 in null-rotation)</field>
<fieldtype="float"name="q4">True attitude quaternion component 4, z (0 in null-rotation)</field>
<fieldtype="float"name="roll">Attitude roll expressed as Euler angles, not recommended except for human-readable outputs</field>
<fieldtype="float"name="pitch">Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs</field>
<fieldtype="float"name="yaw">Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs</field>
@ -2136,7 +2136,7 @@
@@ -2136,7 +2136,7 @@
<messageid="115"name="HIL_STATE_QUATERNION">
<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[4]"name="attitude_quaternion">Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)</field>
<fieldtype="float"name="rollspeed">Body frame roll / phi angular speed (rad/s)</field>