2 // MESSAGE RAW_IMU PACKING
4 #define MAVLINK_MSG_ID_RAW_IMU 27
7 typedef struct __mavlink_raw_imu_t
{
8 uint64_t time_usec
; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
9 int16_t xacc
; /*< X acceleration (raw)*/
10 int16_t yacc
; /*< Y acceleration (raw)*/
11 int16_t zacc
; /*< Z acceleration (raw)*/
12 int16_t xgyro
; /*< Angular speed around X axis (raw)*/
13 int16_t ygyro
; /*< Angular speed around Y axis (raw)*/
14 int16_t zgyro
; /*< Angular speed around Z axis (raw)*/
15 int16_t xmag
; /*< X Magnetic field (raw)*/
16 int16_t ymag
; /*< Y Magnetic field (raw)*/
17 int16_t zmag
; /*< Z Magnetic field (raw)*/
20 #define MAVLINK_MSG_ID_RAW_IMU_LEN 26
21 #define MAVLINK_MSG_ID_RAW_IMU_MIN_LEN 26
22 #define MAVLINK_MSG_ID_27_LEN 26
23 #define MAVLINK_MSG_ID_27_MIN_LEN 26
25 #define MAVLINK_MSG_ID_RAW_IMU_CRC 144
26 #define MAVLINK_MSG_ID_27_CRC 144
30 #if MAVLINK_COMMAND_24BIT
31 #define MAVLINK_MESSAGE_INFO_RAW_IMU { \
35 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
36 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
37 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
38 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \
39 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \
40 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \
41 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \
42 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
43 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
44 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
48 #define MAVLINK_MESSAGE_INFO_RAW_IMU { \
51 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
52 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
53 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
54 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \
55 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \
56 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \
57 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \
58 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
59 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
60 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
66 * @brief Pack a raw_imu message
67 * @param system_id ID of this system
68 * @param component_id ID of this component (e.g. 200 for IMU)
69 * @param msg The MAVLink message to compress the data into
71 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
72 * @param xacc X acceleration (raw)
73 * @param yacc Y acceleration (raw)
74 * @param zacc Z acceleration (raw)
75 * @param xgyro Angular speed around X axis (raw)
76 * @param ygyro Angular speed around Y axis (raw)
77 * @param zgyro Angular speed around Z axis (raw)
78 * @param xmag X Magnetic field (raw)
79 * @param ymag Y Magnetic field (raw)
80 * @param zmag Z Magnetic field (raw)
81 * @return length of the message in bytes (excluding serial stream start sign)
83 static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
84 uint64_t time_usec
, int16_t xacc
, int16_t yacc
, int16_t zacc
, int16_t xgyro
, int16_t ygyro
, int16_t zgyro
, int16_t xmag
, int16_t ymag
, int16_t zmag
)
86 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87 char buf
[MAVLINK_MSG_ID_RAW_IMU_LEN
];
88 _mav_put_uint64_t(buf
, 0, time_usec
);
89 _mav_put_int16_t(buf
, 8, xacc
);
90 _mav_put_int16_t(buf
, 10, yacc
);
91 _mav_put_int16_t(buf
, 12, zacc
);
92 _mav_put_int16_t(buf
, 14, xgyro
);
93 _mav_put_int16_t(buf
, 16, ygyro
);
94 _mav_put_int16_t(buf
, 18, zgyro
);
95 _mav_put_int16_t(buf
, 20, xmag
);
96 _mav_put_int16_t(buf
, 22, ymag
);
97 _mav_put_int16_t(buf
, 24, zmag
);
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_RAW_IMU_LEN
);
101 mavlink_raw_imu_t packet
;
102 packet
.time_usec
= time_usec
;
106 packet
.xgyro
= xgyro
;
107 packet
.ygyro
= ygyro
;
108 packet
.zgyro
= zgyro
;
113 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_RAW_IMU_LEN
);
116 msg
->msgid
= MAVLINK_MSG_ID_RAW_IMU
;
117 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
121 * @brief Pack a raw_imu message on a channel
122 * @param system_id ID of this system
123 * @param component_id ID of this component (e.g. 200 for IMU)
124 * @param chan The MAVLink channel this message will be sent over
125 * @param msg The MAVLink message to compress the data into
126 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
127 * @param xacc X acceleration (raw)
128 * @param yacc Y acceleration (raw)
129 * @param zacc Z acceleration (raw)
130 * @param xgyro Angular speed around X axis (raw)
131 * @param ygyro Angular speed around Y axis (raw)
132 * @param zgyro Angular speed around Z axis (raw)
133 * @param xmag X Magnetic field (raw)
134 * @param ymag Y Magnetic field (raw)
135 * @param zmag Z Magnetic field (raw)
136 * @return length of the message in bytes (excluding serial stream start sign)
138 static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
139 mavlink_message_t
* msg
,
140 uint64_t time_usec
,int16_t xacc
,int16_t yacc
,int16_t zacc
,int16_t xgyro
,int16_t ygyro
,int16_t zgyro
,int16_t xmag
,int16_t ymag
,int16_t zmag
)
142 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
143 char buf
[MAVLINK_MSG_ID_RAW_IMU_LEN
];
144 _mav_put_uint64_t(buf
, 0, time_usec
);
145 _mav_put_int16_t(buf
, 8, xacc
);
146 _mav_put_int16_t(buf
, 10, yacc
);
147 _mav_put_int16_t(buf
, 12, zacc
);
148 _mav_put_int16_t(buf
, 14, xgyro
);
149 _mav_put_int16_t(buf
, 16, ygyro
);
150 _mav_put_int16_t(buf
, 18, zgyro
);
151 _mav_put_int16_t(buf
, 20, xmag
);
152 _mav_put_int16_t(buf
, 22, ymag
);
153 _mav_put_int16_t(buf
, 24, zmag
);
155 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_RAW_IMU_LEN
);
157 mavlink_raw_imu_t packet
;
158 packet
.time_usec
= time_usec
;
162 packet
.xgyro
= xgyro
;
163 packet
.ygyro
= ygyro
;
164 packet
.zgyro
= zgyro
;
169 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_RAW_IMU_LEN
);
172 msg
->msgid
= MAVLINK_MSG_ID_RAW_IMU
;
173 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
177 * @brief Encode a raw_imu struct
179 * @param system_id ID of this system
180 * @param component_id ID of this component (e.g. 200 for IMU)
181 * @param msg The MAVLink message to compress the data into
182 * @param raw_imu C-struct to read the message contents from
184 static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_raw_imu_t
* raw_imu
)
186 return mavlink_msg_raw_imu_pack(system_id
, component_id
, msg
, raw_imu
->time_usec
, raw_imu
->xacc
, raw_imu
->yacc
, raw_imu
->zacc
, raw_imu
->xgyro
, raw_imu
->ygyro
, raw_imu
->zgyro
, raw_imu
->xmag
, raw_imu
->ymag
, raw_imu
->zmag
);
190 * @brief Encode a raw_imu struct on a channel
192 * @param system_id ID of this system
193 * @param component_id ID of this component (e.g. 200 for IMU)
194 * @param chan The MAVLink channel this message will be sent over
195 * @param msg The MAVLink message to compress the data into
196 * @param raw_imu C-struct to read the message contents from
198 static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_raw_imu_t
* raw_imu
)
200 return mavlink_msg_raw_imu_pack_chan(system_id
, component_id
, chan
, msg
, raw_imu
->time_usec
, raw_imu
->xacc
, raw_imu
->yacc
, raw_imu
->zacc
, raw_imu
->xgyro
, raw_imu
->ygyro
, raw_imu
->zgyro
, raw_imu
->xmag
, raw_imu
->ymag
, raw_imu
->zmag
);
204 * @brief Send a raw_imu message
205 * @param chan MAVLink channel to send the message
207 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
208 * @param xacc X acceleration (raw)
209 * @param yacc Y acceleration (raw)
210 * @param zacc Z acceleration (raw)
211 * @param xgyro Angular speed around X axis (raw)
212 * @param ygyro Angular speed around Y axis (raw)
213 * @param zgyro Angular speed around Z axis (raw)
214 * @param xmag X Magnetic field (raw)
215 * @param ymag Y Magnetic field (raw)
216 * @param zmag Z Magnetic field (raw)
218 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
220 static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan
, uint64_t time_usec
, int16_t xacc
, int16_t yacc
, int16_t zacc
, int16_t xgyro
, int16_t ygyro
, int16_t zgyro
, int16_t xmag
, int16_t ymag
, int16_t zmag
)
222 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
223 char buf
[MAVLINK_MSG_ID_RAW_IMU_LEN
];
224 _mav_put_uint64_t(buf
, 0, time_usec
);
225 _mav_put_int16_t(buf
, 8, xacc
);
226 _mav_put_int16_t(buf
, 10, yacc
);
227 _mav_put_int16_t(buf
, 12, zacc
);
228 _mav_put_int16_t(buf
, 14, xgyro
);
229 _mav_put_int16_t(buf
, 16, ygyro
);
230 _mav_put_int16_t(buf
, 18, zgyro
);
231 _mav_put_int16_t(buf
, 20, xmag
);
232 _mav_put_int16_t(buf
, 22, ymag
);
233 _mav_put_int16_t(buf
, 24, zmag
);
235 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, buf
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
237 mavlink_raw_imu_t packet
;
238 packet
.time_usec
= time_usec
;
242 packet
.xgyro
= xgyro
;
243 packet
.ygyro
= ygyro
;
244 packet
.zgyro
= zgyro
;
249 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, (const char *)&packet
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
254 * @brief Send a raw_imu message
255 * @param chan MAVLink channel to send the message
256 * @param struct The MAVLink struct to serialize
258 static inline void mavlink_msg_raw_imu_send_struct(mavlink_channel_t chan
, const mavlink_raw_imu_t
* raw_imu
)
260 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
261 mavlink_msg_raw_imu_send(chan
, raw_imu
->time_usec
, raw_imu
->xacc
, raw_imu
->yacc
, raw_imu
->zacc
, raw_imu
->xgyro
, raw_imu
->ygyro
, raw_imu
->zgyro
, raw_imu
->xmag
, raw_imu
->ymag
, raw_imu
->zmag
);
263 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, (const char *)raw_imu
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
267 #if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
269 This varient of _send() can be used to save stack space by re-using
270 memory from the receive buffer. The caller provides a
271 mavlink_message_t which is the size of a full mavlink message. This
272 is usually the receive buffer for the channel, and allows a reply to an
273 incoming message with minimum stack space usage.
275 static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, int16_t xacc
, int16_t yacc
, int16_t zacc
, int16_t xgyro
, int16_t ygyro
, int16_t zgyro
, int16_t xmag
, int16_t ymag
, int16_t zmag
)
277 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
278 char *buf
= (char *)msgbuf
;
279 _mav_put_uint64_t(buf
, 0, time_usec
);
280 _mav_put_int16_t(buf
, 8, xacc
);
281 _mav_put_int16_t(buf
, 10, yacc
);
282 _mav_put_int16_t(buf
, 12, zacc
);
283 _mav_put_int16_t(buf
, 14, xgyro
);
284 _mav_put_int16_t(buf
, 16, ygyro
);
285 _mav_put_int16_t(buf
, 18, zgyro
);
286 _mav_put_int16_t(buf
, 20, xmag
);
287 _mav_put_int16_t(buf
, 22, ymag
);
288 _mav_put_int16_t(buf
, 24, zmag
);
290 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, buf
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
292 mavlink_raw_imu_t
*packet
= (mavlink_raw_imu_t
*)msgbuf
;
293 packet
->time_usec
= time_usec
;
297 packet
->xgyro
= xgyro
;
298 packet
->ygyro
= ygyro
;
299 packet
->zgyro
= zgyro
;
304 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, (const char *)packet
, MAVLINK_MSG_ID_RAW_IMU_MIN_LEN
, MAVLINK_MSG_ID_RAW_IMU_LEN
, MAVLINK_MSG_ID_RAW_IMU_CRC
);
311 // MESSAGE RAW_IMU UNPACKING
315 * @brief Get field time_usec from raw_imu message
317 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
319 static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t
* msg
)
321 return _MAV_RETURN_uint64_t(msg
, 0);
325 * @brief Get field xacc from raw_imu message
327 * @return X acceleration (raw)
329 static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t
* msg
)
331 return _MAV_RETURN_int16_t(msg
, 8);
335 * @brief Get field yacc from raw_imu message
337 * @return Y acceleration (raw)
339 static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t
* msg
)
341 return _MAV_RETURN_int16_t(msg
, 10);
345 * @brief Get field zacc from raw_imu message
347 * @return Z acceleration (raw)
349 static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t
* msg
)
351 return _MAV_RETURN_int16_t(msg
, 12);
355 * @brief Get field xgyro from raw_imu message
357 * @return Angular speed around X axis (raw)
359 static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t
* msg
)
361 return _MAV_RETURN_int16_t(msg
, 14);
365 * @brief Get field ygyro from raw_imu message
367 * @return Angular speed around Y axis (raw)
369 static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t
* msg
)
371 return _MAV_RETURN_int16_t(msg
, 16);
375 * @brief Get field zgyro from raw_imu message
377 * @return Angular speed around Z axis (raw)
379 static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t
* msg
)
381 return _MAV_RETURN_int16_t(msg
, 18);
385 * @brief Get field xmag from raw_imu message
387 * @return X Magnetic field (raw)
389 static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t
* msg
)
391 return _MAV_RETURN_int16_t(msg
, 20);
395 * @brief Get field ymag from raw_imu message
397 * @return Y Magnetic field (raw)
399 static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t
* msg
)
401 return _MAV_RETURN_int16_t(msg
, 22);
405 * @brief Get field zmag from raw_imu message
407 * @return Z Magnetic field (raw)
409 static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t
* msg
)
411 return _MAV_RETURN_int16_t(msg
, 24);
415 * @brief Decode a raw_imu message into a struct
417 * @param msg The message to decode
418 * @param raw_imu C-struct to decode the message contents into
420 static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t
* msg
, mavlink_raw_imu_t
* raw_imu
)
422 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
423 raw_imu
->time_usec
= mavlink_msg_raw_imu_get_time_usec(msg
);
424 raw_imu
->xacc
= mavlink_msg_raw_imu_get_xacc(msg
);
425 raw_imu
->yacc
= mavlink_msg_raw_imu_get_yacc(msg
);
426 raw_imu
->zacc
= mavlink_msg_raw_imu_get_zacc(msg
);
427 raw_imu
->xgyro
= mavlink_msg_raw_imu_get_xgyro(msg
);
428 raw_imu
->ygyro
= mavlink_msg_raw_imu_get_ygyro(msg
);
429 raw_imu
->zgyro
= mavlink_msg_raw_imu_get_zgyro(msg
);
430 raw_imu
->xmag
= mavlink_msg_raw_imu_get_xmag(msg
);
431 raw_imu
->ymag
= mavlink_msg_raw_imu_get_ymag(msg
);
432 raw_imu
->zmag
= mavlink_msg_raw_imu_get_zmag(msg
);
434 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_RAW_IMU_LEN
? msg
->len
: MAVLINK_MSG_ID_RAW_IMU_LEN
;
435 memset(raw_imu
, 0, MAVLINK_MSG_ID_RAW_IMU_LEN
);
436 memcpy(raw_imu
, _MAV_PAYLOAD(msg
), len
);