1 // MESSAGE RAW_IMU PACKING
3 #define MAVLINK_MSG_ID_RAW_IMU 27
5 typedef struct __mavlink_raw_imu_t
{
6 uint64_t time_usec
; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
7 int16_t xacc
; ///< X acceleration (raw)
8 int16_t yacc
; ///< Y acceleration (raw)
9 int16_t zacc
; ///< Z acceleration (raw)
10 int16_t xgyro
; ///< Angular speed around X axis (raw)
11 int16_t ygyro
; ///< Angular speed around Y axis (raw)
12 int16_t zgyro
; ///< Angular speed around Z axis (raw)
13 int16_t xmag
; ///< X Magnetic field (raw)
14 int16_t ymag
; ///< Y Magnetic field (raw)
15 int16_t zmag
; ///< Z Magnetic field (raw)
18 #define MAVLINK_MSG_ID_RAW_IMU_LEN 26
19 #define MAVLINK_MSG_ID_27_LEN 26
22 #define MAVLINK_MESSAGE_INFO_RAW_IMU \
27 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
28 { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
29 { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
30 { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \
31 { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \
32 { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \
33 { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \
34 { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
35 { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
36 { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
42 * @brief Pack a raw_imu message
43 * @param system_id ID of this system
44 * @param component_id ID of this component (e.g. 200 for IMU)
45 * @param msg The MAVLink message to compress the data into
47 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
48 * @param xacc X acceleration (raw)
49 * @param yacc Y acceleration (raw)
50 * @param zacc Z acceleration (raw)
51 * @param xgyro Angular speed around X axis (raw)
52 * @param ygyro Angular speed around Y axis (raw)
53 * @param zgyro Angular speed around Z axis (raw)
54 * @param xmag X Magnetic field (raw)
55 * @param ymag Y Magnetic field (raw)
56 * @param zmag Z Magnetic field (raw)
57 * @return length of the message in bytes (excluding serial stream start sign)
59 static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
60 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
)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
64 _mav_put_uint64_t(buf
, 0, time_usec
);
65 _mav_put_int16_t(buf
, 8, xacc
);
66 _mav_put_int16_t(buf
, 10, yacc
);
67 _mav_put_int16_t(buf
, 12, zacc
);
68 _mav_put_int16_t(buf
, 14, xgyro
);
69 _mav_put_int16_t(buf
, 16, ygyro
);
70 _mav_put_int16_t(buf
, 18, zgyro
);
71 _mav_put_int16_t(buf
, 20, xmag
);
72 _mav_put_int16_t(buf
, 22, ymag
);
73 _mav_put_int16_t(buf
, 24, zmag
);
75 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 26);
77 mavlink_raw_imu_t packet
;
78 packet
.time_usec
= time_usec
;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 26);
90 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
92 msg
->msgid
= MAVLINK_MSG_ID_RAW_IMU
;
93 return mavlink_finalize_message(msg
, system_id
, component_id
, 26, 144);
97 * @brief Pack a raw_imu message on a channel
98 * @param system_id ID of this system
99 * @param component_id ID of this component (e.g. 200 for IMU)
100 * @param chan The MAVLink channel this message was sent over
101 * @param msg The MAVLink message to compress the data into
102 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
103 * @param xacc X acceleration (raw)
104 * @param yacc Y acceleration (raw)
105 * @param zacc Z acceleration (raw)
106 * @param xgyro Angular speed around X axis (raw)
107 * @param ygyro Angular speed around Y axis (raw)
108 * @param zgyro Angular speed around Z axis (raw)
109 * @param xmag X Magnetic field (raw)
110 * @param ymag Y Magnetic field (raw)
111 * @param zmag Z Magnetic field (raw)
112 * @return length of the message in bytes (excluding serial stream start sign)
114 static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
115 mavlink_message_t
*msg
,
116 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
)
118 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
120 _mav_put_uint64_t(buf
, 0, time_usec
);
121 _mav_put_int16_t(buf
, 8, xacc
);
122 _mav_put_int16_t(buf
, 10, yacc
);
123 _mav_put_int16_t(buf
, 12, zacc
);
124 _mav_put_int16_t(buf
, 14, xgyro
);
125 _mav_put_int16_t(buf
, 16, ygyro
);
126 _mav_put_int16_t(buf
, 18, zgyro
);
127 _mav_put_int16_t(buf
, 20, xmag
);
128 _mav_put_int16_t(buf
, 22, ymag
);
129 _mav_put_int16_t(buf
, 24, zmag
);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 26);
133 mavlink_raw_imu_t packet
;
134 packet
.time_usec
= time_usec
;
138 packet
.xgyro
= xgyro
;
139 packet
.ygyro
= ygyro
;
140 packet
.zgyro
= zgyro
;
145 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 26);
146 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
148 msg
->msgid
= MAVLINK_MSG_ID_RAW_IMU
;
149 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 26, 144);
153 * @brief Encode a raw_imu struct into a message
155 * @param system_id ID of this system
156 * @param component_id ID of this component (e.g. 200 for IMU)
157 * @param msg The MAVLink message to compress the data into
158 * @param raw_imu C-struct to read the message contents from
160 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
)
162 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
);
166 * @brief Send a raw_imu message
167 * @param chan MAVLink channel to send the message
169 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
170 * @param xacc X acceleration (raw)
171 * @param yacc Y acceleration (raw)
172 * @param zacc Z acceleration (raw)
173 * @param xgyro Angular speed around X axis (raw)
174 * @param ygyro Angular speed around Y axis (raw)
175 * @param zgyro Angular speed around Z axis (raw)
176 * @param xmag X Magnetic field (raw)
177 * @param ymag Y Magnetic field (raw)
178 * @param zmag Z Magnetic field (raw)
180 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
182 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
)
184 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
186 _mav_put_uint64_t(buf
, 0, time_usec
);
187 _mav_put_int16_t(buf
, 8, xacc
);
188 _mav_put_int16_t(buf
, 10, yacc
);
189 _mav_put_int16_t(buf
, 12, zacc
);
190 _mav_put_int16_t(buf
, 14, xgyro
);
191 _mav_put_int16_t(buf
, 16, ygyro
);
192 _mav_put_int16_t(buf
, 18, zgyro
);
193 _mav_put_int16_t(buf
, 20, xmag
);
194 _mav_put_int16_t(buf
, 22, ymag
);
195 _mav_put_int16_t(buf
, 24, zmag
);
197 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, buf
, 26, 144);
199 mavlink_raw_imu_t packet
;
200 packet
.time_usec
= time_usec
;
204 packet
.xgyro
= xgyro
;
205 packet
.ygyro
= ygyro
;
206 packet
.zgyro
= zgyro
;
211 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_RAW_IMU
, (const char *)&packet
, 26, 144);
212 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
217 // MESSAGE RAW_IMU UNPACKING
221 * @brief Get field time_usec from raw_imu message
223 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
225 static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t
*msg
)
227 return _MAV_RETURN_uint64_t(msg
, 0);
231 * @brief Get field xacc from raw_imu message
233 * @return X acceleration (raw)
235 static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t
*msg
)
237 return _MAV_RETURN_int16_t(msg
, 8);
241 * @brief Get field yacc from raw_imu message
243 * @return Y acceleration (raw)
245 static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t
*msg
)
247 return _MAV_RETURN_int16_t(msg
, 10);
251 * @brief Get field zacc from raw_imu message
253 * @return Z acceleration (raw)
255 static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t
*msg
)
257 return _MAV_RETURN_int16_t(msg
, 12);
261 * @brief Get field xgyro from raw_imu message
263 * @return Angular speed around X axis (raw)
265 static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t
*msg
)
267 return _MAV_RETURN_int16_t(msg
, 14);
271 * @brief Get field ygyro from raw_imu message
273 * @return Angular speed around Y axis (raw)
275 static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t
*msg
)
277 return _MAV_RETURN_int16_t(msg
, 16);
281 * @brief Get field zgyro from raw_imu message
283 * @return Angular speed around Z axis (raw)
285 static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t
*msg
)
287 return _MAV_RETURN_int16_t(msg
, 18);
291 * @brief Get field xmag from raw_imu message
293 * @return X Magnetic field (raw)
295 static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t
*msg
)
297 return _MAV_RETURN_int16_t(msg
, 20);
301 * @brief Get field ymag from raw_imu message
303 * @return Y Magnetic field (raw)
305 static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t
*msg
)
307 return _MAV_RETURN_int16_t(msg
, 22);
311 * @brief Get field zmag from raw_imu message
313 * @return Z Magnetic field (raw)
315 static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t
*msg
)
317 return _MAV_RETURN_int16_t(msg
, 24);
321 * @brief Decode a raw_imu message into a struct
323 * @param msg The message to decode
324 * @param raw_imu C-struct to decode the message contents into
326 static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t
*msg
, mavlink_raw_imu_t
*raw_imu
)
328 #if MAVLINK_NEED_BYTE_SWAP
329 raw_imu
->time_usec
= mavlink_msg_raw_imu_get_time_usec(msg
);
330 raw_imu
->xacc
= mavlink_msg_raw_imu_get_xacc(msg
);
331 raw_imu
->yacc
= mavlink_msg_raw_imu_get_yacc(msg
);
332 raw_imu
->zacc
= mavlink_msg_raw_imu_get_zacc(msg
);
333 raw_imu
->xgyro
= mavlink_msg_raw_imu_get_xgyro(msg
);
334 raw_imu
->ygyro
= mavlink_msg_raw_imu_get_ygyro(msg
);
335 raw_imu
->zgyro
= mavlink_msg_raw_imu_get_zgyro(msg
);
336 raw_imu
->xmag
= mavlink_msg_raw_imu_get_xmag(msg
);
337 raw_imu
->ymag
= mavlink_msg_raw_imu_get_ymag(msg
);
338 raw_imu
->zmag
= mavlink_msg_raw_imu_get_zmag(msg
);
340 memcpy(raw_imu
, _MAV_PAYLOAD(msg
), 26);