2 // MESSAGE ATTITUDE_QUATERNION PACKING
4 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
7 typedef struct __mavlink_attitude_quaternion_t
{
8 uint32_t time_boot_ms
; /*< [ms] Timestamp (time since system boot).*/
9 float q1
; /*< Quaternion component 1, w (1 in null-rotation)*/
10 float q2
; /*< Quaternion component 2, x (0 in null-rotation)*/
11 float q3
; /*< Quaternion component 3, y (0 in null-rotation)*/
12 float q4
; /*< Quaternion component 4, z (0 in null-rotation)*/
13 float rollspeed
; /*< [rad/s] Roll angular speed*/
14 float pitchspeed
; /*< [rad/s] Pitch angular speed*/
15 float yawspeed
; /*< [rad/s] Yaw angular speed*/
16 float repr_offset_q
[4]; /*< Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.*/
17 } mavlink_attitude_quaternion_t
;
19 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 48
20 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
21 #define MAVLINK_MSG_ID_31_LEN 48
22 #define MAVLINK_MSG_ID_31_MIN_LEN 32
24 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
25 #define MAVLINK_MSG_ID_31_CRC 246
27 #define MAVLINK_MSG_ATTITUDE_QUATERNION_FIELD_REPR_OFFSET_Q_LEN 4
29 #if MAVLINK_COMMAND_24BIT
30 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
32 "ATTITUDE_QUATERNION", \
34 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
35 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
36 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
37 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
38 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
39 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
40 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
41 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
42 { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
46 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
47 "ATTITUDE_QUATERNION", \
49 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
50 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
51 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
52 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
53 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
54 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
55 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
56 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
57 { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
63 * @brief Pack a attitude_quaternion message
64 * @param system_id ID of this system
65 * @param component_id ID of this component (e.g. 200 for IMU)
66 * @param msg The MAVLink message to compress the data into
68 * @param time_boot_ms [ms] Timestamp (time since system boot).
69 * @param q1 Quaternion component 1, w (1 in null-rotation)
70 * @param q2 Quaternion component 2, x (0 in null-rotation)
71 * @param q3 Quaternion component 3, y (0 in null-rotation)
72 * @param q4 Quaternion component 4, z (0 in null-rotation)
73 * @param rollspeed [rad/s] Roll angular speed
74 * @param pitchspeed [rad/s] Pitch angular speed
75 * @param yawspeed [rad/s] Yaw angular speed
76 * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
77 * @return length of the message in bytes (excluding serial stream start sign)
79 static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
80 uint32_t time_boot_ms
, float q1
, float q2
, float q3
, float q4
, float rollspeed
, float pitchspeed
, float yawspeed
, const float *repr_offset_q
)
82 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
84 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
85 _mav_put_float(buf
, 4, q1
);
86 _mav_put_float(buf
, 8, q2
);
87 _mav_put_float(buf
, 12, q3
);
88 _mav_put_float(buf
, 16, q4
);
89 _mav_put_float(buf
, 20, rollspeed
);
90 _mav_put_float(buf
, 24, pitchspeed
);
91 _mav_put_float(buf
, 28, yawspeed
);
92 _mav_put_float_array(buf
, 32, repr_offset_q
, 4);
93 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
95 mavlink_attitude_quaternion_t packet
;
96 packet
.time_boot_ms
= time_boot_ms
;
101 packet
.rollspeed
= rollspeed
;
102 packet
.pitchspeed
= pitchspeed
;
103 packet
.yawspeed
= yawspeed
;
104 mav_array_memcpy(packet
.repr_offset_q
, repr_offset_q
, sizeof(float)*4);
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
108 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_QUATERNION
;
109 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
113 * @brief Pack a attitude_quaternion message on a channel
114 * @param system_id ID of this system
115 * @param component_id ID of this component (e.g. 200 for IMU)
116 * @param chan The MAVLink channel this message will be sent over
117 * @param msg The MAVLink message to compress the data into
118 * @param time_boot_ms [ms] Timestamp (time since system boot).
119 * @param q1 Quaternion component 1, w (1 in null-rotation)
120 * @param q2 Quaternion component 2, x (0 in null-rotation)
121 * @param q3 Quaternion component 3, y (0 in null-rotation)
122 * @param q4 Quaternion component 4, z (0 in null-rotation)
123 * @param rollspeed [rad/s] Roll angular speed
124 * @param pitchspeed [rad/s] Pitch angular speed
125 * @param yawspeed [rad/s] Yaw angular speed
126 * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
127 * @return length of the message in bytes (excluding serial stream start sign)
129 static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
130 mavlink_message_t
* msg
,
131 uint32_t time_boot_ms
,float q1
,float q2
,float q3
,float q4
,float rollspeed
,float pitchspeed
,float yawspeed
,const float *repr_offset_q
)
133 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
134 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
135 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
136 _mav_put_float(buf
, 4, q1
);
137 _mav_put_float(buf
, 8, q2
);
138 _mav_put_float(buf
, 12, q3
);
139 _mav_put_float(buf
, 16, q4
);
140 _mav_put_float(buf
, 20, rollspeed
);
141 _mav_put_float(buf
, 24, pitchspeed
);
142 _mav_put_float(buf
, 28, yawspeed
);
143 _mav_put_float_array(buf
, 32, repr_offset_q
, 4);
144 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
146 mavlink_attitude_quaternion_t packet
;
147 packet
.time_boot_ms
= time_boot_ms
;
152 packet
.rollspeed
= rollspeed
;
153 packet
.pitchspeed
= pitchspeed
;
154 packet
.yawspeed
= yawspeed
;
155 mav_array_memcpy(packet
.repr_offset_q
, repr_offset_q
, sizeof(float)*4);
156 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
159 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_QUATERNION
;
160 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
164 * @brief Encode a attitude_quaternion struct
166 * @param system_id ID of this system
167 * @param component_id ID of this component (e.g. 200 for IMU)
168 * @param msg The MAVLink message to compress the data into
169 * @param attitude_quaternion C-struct to read the message contents from
171 static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_attitude_quaternion_t
* attitude_quaternion
)
173 return mavlink_msg_attitude_quaternion_pack(system_id
, component_id
, msg
, attitude_quaternion
->time_boot_ms
, attitude_quaternion
->q1
, attitude_quaternion
->q2
, attitude_quaternion
->q3
, attitude_quaternion
->q4
, attitude_quaternion
->rollspeed
, attitude_quaternion
->pitchspeed
, attitude_quaternion
->yawspeed
, attitude_quaternion
->repr_offset_q
);
177 * @brief Encode a attitude_quaternion struct on a channel
179 * @param system_id ID of this system
180 * @param component_id ID of this component (e.g. 200 for IMU)
181 * @param chan The MAVLink channel this message will be sent over
182 * @param msg The MAVLink message to compress the data into
183 * @param attitude_quaternion C-struct to read the message contents from
185 static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_attitude_quaternion_t
* attitude_quaternion
)
187 return mavlink_msg_attitude_quaternion_pack_chan(system_id
, component_id
, chan
, msg
, attitude_quaternion
->time_boot_ms
, attitude_quaternion
->q1
, attitude_quaternion
->q2
, attitude_quaternion
->q3
, attitude_quaternion
->q4
, attitude_quaternion
->rollspeed
, attitude_quaternion
->pitchspeed
, attitude_quaternion
->yawspeed
, attitude_quaternion
->repr_offset_q
);
191 * @brief Send a attitude_quaternion message
192 * @param chan MAVLink channel to send the message
194 * @param time_boot_ms [ms] Timestamp (time since system boot).
195 * @param q1 Quaternion component 1, w (1 in null-rotation)
196 * @param q2 Quaternion component 2, x (0 in null-rotation)
197 * @param q3 Quaternion component 3, y (0 in null-rotation)
198 * @param q4 Quaternion component 4, z (0 in null-rotation)
199 * @param rollspeed [rad/s] Roll angular speed
200 * @param pitchspeed [rad/s] Pitch angular speed
201 * @param yawspeed [rad/s] Yaw angular speed
202 * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
204 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
206 static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan
, uint32_t time_boot_ms
, float q1
, float q2
, float q3
, float q4
, float rollspeed
, float pitchspeed
, float yawspeed
, const float *repr_offset_q
)
208 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
209 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
210 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
211 _mav_put_float(buf
, 4, q1
);
212 _mav_put_float(buf
, 8, q2
);
213 _mav_put_float(buf
, 12, q3
);
214 _mav_put_float(buf
, 16, q4
);
215 _mav_put_float(buf
, 20, rollspeed
);
216 _mav_put_float(buf
, 24, pitchspeed
);
217 _mav_put_float(buf
, 28, yawspeed
);
218 _mav_put_float_array(buf
, 32, repr_offset_q
, 4);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION
, buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
221 mavlink_attitude_quaternion_t packet
;
222 packet
.time_boot_ms
= time_boot_ms
;
227 packet
.rollspeed
= rollspeed
;
228 packet
.pitchspeed
= pitchspeed
;
229 packet
.yawspeed
= yawspeed
;
230 mav_array_memcpy(packet
.repr_offset_q
, repr_offset_q
, sizeof(float)*4);
231 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
236 * @brief Send a attitude_quaternion message
237 * @param chan MAVLink channel to send the message
238 * @param struct The MAVLink struct to serialize
240 static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan
, const mavlink_attitude_quaternion_t
* attitude_quaternion
)
242 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
243 mavlink_msg_attitude_quaternion_send(chan
, attitude_quaternion
->time_boot_ms
, attitude_quaternion
->q1
, attitude_quaternion
->q2
, attitude_quaternion
->q3
, attitude_quaternion
->q4
, attitude_quaternion
->rollspeed
, attitude_quaternion
->pitchspeed
, attitude_quaternion
->yawspeed
, attitude_quaternion
->repr_offset_q
);
245 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION
, (const char *)attitude_quaternion
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
249 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
251 This varient of _send() can be used to save stack space by re-using
252 memory from the receive buffer. The caller provides a
253 mavlink_message_t which is the size of a full mavlink message. This
254 is usually the receive buffer for the channel, and allows a reply to an
255 incoming message with minimum stack space usage.
257 static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint32_t time_boot_ms
, float q1
, float q2
, float q3
, float q4
, float rollspeed
, float pitchspeed
, float yawspeed
, const float *repr_offset_q
)
259 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
260 char *buf
= (char *)msgbuf
;
261 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
262 _mav_put_float(buf
, 4, q1
);
263 _mav_put_float(buf
, 8, q2
);
264 _mav_put_float(buf
, 12, q3
);
265 _mav_put_float(buf
, 16, q4
);
266 _mav_put_float(buf
, 20, rollspeed
);
267 _mav_put_float(buf
, 24, pitchspeed
);
268 _mav_put_float(buf
, 28, yawspeed
);
269 _mav_put_float_array(buf
, 32, repr_offset_q
, 4);
270 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION
, buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
272 mavlink_attitude_quaternion_t
*packet
= (mavlink_attitude_quaternion_t
*)msgbuf
;
273 packet
->time_boot_ms
= time_boot_ms
;
278 packet
->rollspeed
= rollspeed
;
279 packet
->pitchspeed
= pitchspeed
;
280 packet
->yawspeed
= yawspeed
;
281 mav_array_memcpy(packet
->repr_offset_q
, repr_offset_q
, sizeof(float)*4);
282 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC
);
289 // MESSAGE ATTITUDE_QUATERNION UNPACKING
293 * @brief Get field time_boot_ms from attitude_quaternion message
295 * @return [ms] Timestamp (time since system boot).
297 static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t
* msg
)
299 return _MAV_RETURN_uint32_t(msg
, 0);
303 * @brief Get field q1 from attitude_quaternion message
305 * @return Quaternion component 1, w (1 in null-rotation)
307 static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t
* msg
)
309 return _MAV_RETURN_float(msg
, 4);
313 * @brief Get field q2 from attitude_quaternion message
315 * @return Quaternion component 2, x (0 in null-rotation)
317 static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t
* msg
)
319 return _MAV_RETURN_float(msg
, 8);
323 * @brief Get field q3 from attitude_quaternion message
325 * @return Quaternion component 3, y (0 in null-rotation)
327 static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t
* msg
)
329 return _MAV_RETURN_float(msg
, 12);
333 * @brief Get field q4 from attitude_quaternion message
335 * @return Quaternion component 4, z (0 in null-rotation)
337 static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t
* msg
)
339 return _MAV_RETURN_float(msg
, 16);
343 * @brief Get field rollspeed from attitude_quaternion message
345 * @return [rad/s] Roll angular speed
347 static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t
* msg
)
349 return _MAV_RETURN_float(msg
, 20);
353 * @brief Get field pitchspeed from attitude_quaternion message
355 * @return [rad/s] Pitch angular speed
357 static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t
* msg
)
359 return _MAV_RETURN_float(msg
, 24);
363 * @brief Get field yawspeed from attitude_quaternion message
365 * @return [rad/s] Yaw angular speed
367 static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t
* msg
)
369 return _MAV_RETURN_float(msg
, 28);
373 * @brief Get field repr_offset_q from attitude_quaternion message
375 * @return Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
377 static inline uint16_t mavlink_msg_attitude_quaternion_get_repr_offset_q(const mavlink_message_t
* msg
, float *repr_offset_q
)
379 return _MAV_RETURN_float_array(msg
, repr_offset_q
, 4, 32);
383 * @brief Decode a attitude_quaternion message into a struct
385 * @param msg The message to decode
386 * @param attitude_quaternion C-struct to decode the message contents into
388 static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t
* msg
, mavlink_attitude_quaternion_t
* attitude_quaternion
)
390 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
391 attitude_quaternion
->time_boot_ms
= mavlink_msg_attitude_quaternion_get_time_boot_ms(msg
);
392 attitude_quaternion
->q1
= mavlink_msg_attitude_quaternion_get_q1(msg
);
393 attitude_quaternion
->q2
= mavlink_msg_attitude_quaternion_get_q2(msg
);
394 attitude_quaternion
->q3
= mavlink_msg_attitude_quaternion_get_q3(msg
);
395 attitude_quaternion
->q4
= mavlink_msg_attitude_quaternion_get_q4(msg
);
396 attitude_quaternion
->rollspeed
= mavlink_msg_attitude_quaternion_get_rollspeed(msg
);
397 attitude_quaternion
->pitchspeed
= mavlink_msg_attitude_quaternion_get_pitchspeed(msg
);
398 attitude_quaternion
->yawspeed
= mavlink_msg_attitude_quaternion_get_yawspeed(msg
);
399 mavlink_msg_attitude_quaternion_get_repr_offset_q(msg
, attitude_quaternion
->repr_offset_q
);
401 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
? msg
->len
: MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
;
402 memset(attitude_quaternion
, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
403 memcpy(attitude_quaternion
, _MAV_PAYLOAD(msg
), len
);