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
; /*< Timestamp (milliseconds 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
; /*< Roll angular speed (rad/s)*/
14 float pitchspeed
; /*< Pitch angular speed (rad/s)*/
15 float yawspeed
; /*< Yaw angular speed (rad/s)*/
16 }) mavlink_attitude_quaternion_t
;
18 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
19 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
20 #define MAVLINK_MSG_ID_31_LEN 32
21 #define MAVLINK_MSG_ID_31_MIN_LEN 32
23 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
24 #define MAVLINK_MSG_ID_31_CRC 246
28 #if MAVLINK_COMMAND_24BIT
29 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
31 "ATTITUDE_QUATERNION", \
33 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
34 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
35 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
36 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
37 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
38 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
39 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
40 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
44 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
45 "ATTITUDE_QUATERNION", \
47 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
48 { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
49 { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
50 { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
51 { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
52 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
53 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
54 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
60 * @brief Pack a attitude_quaternion message
61 * @param system_id ID of this system
62 * @param component_id ID of this component (e.g. 200 for IMU)
63 * @param msg The MAVLink message to compress the data into
65 * @param time_boot_ms Timestamp (milliseconds since system boot)
66 * @param q1 Quaternion component 1, w (1 in null-rotation)
67 * @param q2 Quaternion component 2, x (0 in null-rotation)
68 * @param q3 Quaternion component 3, y (0 in null-rotation)
69 * @param q4 Quaternion component 4, z (0 in null-rotation)
70 * @param rollspeed Roll angular speed (rad/s)
71 * @param pitchspeed Pitch angular speed (rad/s)
72 * @param yawspeed Yaw angular speed (rad/s)
73 * @return length of the message in bytes (excluding serial stream start sign)
75 static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
76 uint32_t time_boot_ms
, float q1
, float q2
, float q3
, float q4
, float rollspeed
, float pitchspeed
, float yawspeed
)
78 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
80 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
81 _mav_put_float(buf
, 4, q1
);
82 _mav_put_float(buf
, 8, q2
);
83 _mav_put_float(buf
, 12, q3
);
84 _mav_put_float(buf
, 16, q4
);
85 _mav_put_float(buf
, 20, rollspeed
);
86 _mav_put_float(buf
, 24, pitchspeed
);
87 _mav_put_float(buf
, 28, yawspeed
);
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
91 mavlink_attitude_quaternion_t packet
;
92 packet
.time_boot_ms
= time_boot_ms
;
97 packet
.rollspeed
= rollspeed
;
98 packet
.pitchspeed
= pitchspeed
;
99 packet
.yawspeed
= yawspeed
;
101 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
104 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_QUATERNION
;
105 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
);
109 * @brief Pack a attitude_quaternion message on a channel
110 * @param system_id ID of this system
111 * @param component_id ID of this component (e.g. 200 for IMU)
112 * @param chan The MAVLink channel this message will be sent over
113 * @param msg The MAVLink message to compress the data into
114 * @param time_boot_ms Timestamp (milliseconds since system boot)
115 * @param q1 Quaternion component 1, w (1 in null-rotation)
116 * @param q2 Quaternion component 2, x (0 in null-rotation)
117 * @param q3 Quaternion component 3, y (0 in null-rotation)
118 * @param q4 Quaternion component 4, z (0 in null-rotation)
119 * @param rollspeed Roll angular speed (rad/s)
120 * @param pitchspeed Pitch angular speed (rad/s)
121 * @param yawspeed Yaw angular speed (rad/s)
122 * @return length of the message in bytes (excluding serial stream start sign)
124 static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
125 mavlink_message_t
* msg
,
126 uint32_t time_boot_ms
,float q1
,float q2
,float q3
,float q4
,float rollspeed
,float pitchspeed
,float yawspeed
)
128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
129 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
130 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
131 _mav_put_float(buf
, 4, q1
);
132 _mav_put_float(buf
, 8, q2
);
133 _mav_put_float(buf
, 12, q3
);
134 _mav_put_float(buf
, 16, q4
);
135 _mav_put_float(buf
, 20, rollspeed
);
136 _mav_put_float(buf
, 24, pitchspeed
);
137 _mav_put_float(buf
, 28, yawspeed
);
139 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
141 mavlink_attitude_quaternion_t packet
;
142 packet
.time_boot_ms
= time_boot_ms
;
147 packet
.rollspeed
= rollspeed
;
148 packet
.pitchspeed
= pitchspeed
;
149 packet
.yawspeed
= yawspeed
;
151 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
154 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE_QUATERNION
;
155 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
);
159 * @brief Encode a attitude_quaternion struct
161 * @param system_id ID of this system
162 * @param component_id ID of this component (e.g. 200 for IMU)
163 * @param msg The MAVLink message to compress the data into
164 * @param attitude_quaternion C-struct to read the message contents from
166 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
)
168 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
);
172 * @brief Encode a attitude_quaternion struct on a channel
174 * @param system_id ID of this system
175 * @param component_id ID of this component (e.g. 200 for IMU)
176 * @param chan The MAVLink channel this message will be sent over
177 * @param msg The MAVLink message to compress the data into
178 * @param attitude_quaternion C-struct to read the message contents from
180 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
)
182 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
);
186 * @brief Send a attitude_quaternion message
187 * @param chan MAVLink channel to send the message
189 * @param time_boot_ms Timestamp (milliseconds since system boot)
190 * @param q1 Quaternion component 1, w (1 in null-rotation)
191 * @param q2 Quaternion component 2, x (0 in null-rotation)
192 * @param q3 Quaternion component 3, y (0 in null-rotation)
193 * @param q4 Quaternion component 4, z (0 in null-rotation)
194 * @param rollspeed Roll angular speed (rad/s)
195 * @param pitchspeed Pitch angular speed (rad/s)
196 * @param yawspeed Yaw angular speed (rad/s)
198 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
200 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
)
202 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
203 char buf
[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
];
204 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
205 _mav_put_float(buf
, 4, q1
);
206 _mav_put_float(buf
, 8, q2
);
207 _mav_put_float(buf
, 12, q3
);
208 _mav_put_float(buf
, 16, q4
);
209 _mav_put_float(buf
, 20, rollspeed
);
210 _mav_put_float(buf
, 24, pitchspeed
);
211 _mav_put_float(buf
, 28, yawspeed
);
213 _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
);
215 mavlink_attitude_quaternion_t packet
;
216 packet
.time_boot_ms
= time_boot_ms
;
221 packet
.rollspeed
= rollspeed
;
222 packet
.pitchspeed
= pitchspeed
;
223 packet
.yawspeed
= yawspeed
;
225 _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
);
230 * @brief Send a attitude_quaternion message
231 * @param chan MAVLink channel to send the message
232 * @param struct The MAVLink struct to serialize
234 static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan
, const mavlink_attitude_quaternion_t
* attitude_quaternion
)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237 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
);
239 _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
);
243 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
245 This varient of _send() can be used to save stack space by re-using
246 memory from the receive buffer. The caller provides a
247 mavlink_message_t which is the size of a full mavlink message. This
248 is usually the receive buffer for the channel, and allows a reply to an
249 incoming message with minimum stack space usage.
251 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
)
253 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
254 char *buf
= (char *)msgbuf
;
255 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
256 _mav_put_float(buf
, 4, q1
);
257 _mav_put_float(buf
, 8, q2
);
258 _mav_put_float(buf
, 12, q3
);
259 _mav_put_float(buf
, 16, q4
);
260 _mav_put_float(buf
, 20, rollspeed
);
261 _mav_put_float(buf
, 24, pitchspeed
);
262 _mav_put_float(buf
, 28, yawspeed
);
264 _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
);
266 mavlink_attitude_quaternion_t
*packet
= (mavlink_attitude_quaternion_t
*)msgbuf
;
267 packet
->time_boot_ms
= time_boot_ms
;
272 packet
->rollspeed
= rollspeed
;
273 packet
->pitchspeed
= pitchspeed
;
274 packet
->yawspeed
= yawspeed
;
276 _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
);
283 // MESSAGE ATTITUDE_QUATERNION UNPACKING
287 * @brief Get field time_boot_ms from attitude_quaternion message
289 * @return Timestamp (milliseconds since system boot)
291 static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t
* msg
)
293 return _MAV_RETURN_uint32_t(msg
, 0);
297 * @brief Get field q1 from attitude_quaternion message
299 * @return Quaternion component 1, w (1 in null-rotation)
301 static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t
* msg
)
303 return _MAV_RETURN_float(msg
, 4);
307 * @brief Get field q2 from attitude_quaternion message
309 * @return Quaternion component 2, x (0 in null-rotation)
311 static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t
* msg
)
313 return _MAV_RETURN_float(msg
, 8);
317 * @brief Get field q3 from attitude_quaternion message
319 * @return Quaternion component 3, y (0 in null-rotation)
321 static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t
* msg
)
323 return _MAV_RETURN_float(msg
, 12);
327 * @brief Get field q4 from attitude_quaternion message
329 * @return Quaternion component 4, z (0 in null-rotation)
331 static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t
* msg
)
333 return _MAV_RETURN_float(msg
, 16);
337 * @brief Get field rollspeed from attitude_quaternion message
339 * @return Roll angular speed (rad/s)
341 static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t
* msg
)
343 return _MAV_RETURN_float(msg
, 20);
347 * @brief Get field pitchspeed from attitude_quaternion message
349 * @return Pitch angular speed (rad/s)
351 static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t
* msg
)
353 return _MAV_RETURN_float(msg
, 24);
357 * @brief Get field yawspeed from attitude_quaternion message
359 * @return Yaw angular speed (rad/s)
361 static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t
* msg
)
363 return _MAV_RETURN_float(msg
, 28);
367 * @brief Decode a attitude_quaternion message into a struct
369 * @param msg The message to decode
370 * @param attitude_quaternion C-struct to decode the message contents into
372 static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t
* msg
, mavlink_attitude_quaternion_t
* attitude_quaternion
)
374 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
375 attitude_quaternion
->time_boot_ms
= mavlink_msg_attitude_quaternion_get_time_boot_ms(msg
);
376 attitude_quaternion
->q1
= mavlink_msg_attitude_quaternion_get_q1(msg
);
377 attitude_quaternion
->q2
= mavlink_msg_attitude_quaternion_get_q2(msg
);
378 attitude_quaternion
->q3
= mavlink_msg_attitude_quaternion_get_q3(msg
);
379 attitude_quaternion
->q4
= mavlink_msg_attitude_quaternion_get_q4(msg
);
380 attitude_quaternion
->rollspeed
= mavlink_msg_attitude_quaternion_get_rollspeed(msg
);
381 attitude_quaternion
->pitchspeed
= mavlink_msg_attitude_quaternion_get_pitchspeed(msg
);
382 attitude_quaternion
->yawspeed
= mavlink_msg_attitude_quaternion_get_yawspeed(msg
);
384 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
? msg
->len
: MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
;
385 memset(attitude_quaternion
, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN
);
386 memcpy(attitude_quaternion
, _MAV_PAYLOAD(msg
), len
);