1 // MESSAGE HIGHRES_IMU PACKING
3 #define MAVLINK_MSG_ID_HIGHRES_IMU 105
5 typedef struct __mavlink_highres_imu_t
7 uint64_t time_usec
; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
8 float xacc
; ///< X acceleration (m/s^2)
9 float yacc
; ///< Y acceleration (m/s^2)
10 float zacc
; ///< Z acceleration (m/s^2)
11 float xgyro
; ///< Angular speed around X axis (rad / sec)
12 float ygyro
; ///< Angular speed around Y axis (rad / sec)
13 float zgyro
; ///< Angular speed around Z axis (rad / sec)
14 float xmag
; ///< X Magnetic field (Gauss)
15 float ymag
; ///< Y Magnetic field (Gauss)
16 float zmag
; ///< Z Magnetic field (Gauss)
17 float abs_pressure
; ///< Absolute pressure in millibar
18 float diff_pressure
; ///< Differential pressure in millibar
19 float pressure_alt
; ///< Altitude calculated from pressure
20 float temperature
; ///< Temperature in degrees celsius
21 uint16_t fields_updated
; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
22 } mavlink_highres_imu_t
;
24 #define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
25 #define MAVLINK_MSG_ID_105_LEN 62
27 #define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93
28 #define MAVLINK_MSG_ID_105_CRC 93
32 #define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \
35 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \
36 { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \
37 { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \
38 { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \
39 { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \
40 { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \
41 { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \
42 { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \
43 { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \
44 { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \
45 { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \
46 { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \
47 { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \
48 { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \
49 { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \
55 * @brief Pack a highres_imu message
56 * @param system_id ID of this system
57 * @param component_id ID of this component (e.g. 200 for IMU)
58 * @param msg The MAVLink message to compress the data into
60 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
61 * @param xacc X acceleration (m/s^2)
62 * @param yacc Y acceleration (m/s^2)
63 * @param zacc Z acceleration (m/s^2)
64 * @param xgyro Angular speed around X axis (rad / sec)
65 * @param ygyro Angular speed around Y axis (rad / sec)
66 * @param zgyro Angular speed around Z axis (rad / sec)
67 * @param xmag X Magnetic field (Gauss)
68 * @param ymag Y Magnetic field (Gauss)
69 * @param zmag Z Magnetic field (Gauss)
70 * @param abs_pressure Absolute pressure in millibar
71 * @param diff_pressure Differential pressure in millibar
72 * @param pressure_alt Altitude calculated from pressure
73 * @param temperature Temperature in degrees celsius
74 * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
75 * @return length of the message in bytes (excluding serial stream start sign)
77 static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
78 uint64_t time_usec
, float xacc
, float yacc
, float zacc
, float xgyro
, float ygyro
, float zgyro
, float xmag
, float ymag
, float zmag
, float abs_pressure
, float diff_pressure
, float pressure_alt
, float temperature
, uint16_t fields_updated
)
80 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
81 char buf
[MAVLINK_MSG_ID_HIGHRES_IMU_LEN
];
82 _mav_put_uint64_t(buf
, 0, time_usec
);
83 _mav_put_float(buf
, 8, xacc
);
84 _mav_put_float(buf
, 12, yacc
);
85 _mav_put_float(buf
, 16, zacc
);
86 _mav_put_float(buf
, 20, xgyro
);
87 _mav_put_float(buf
, 24, ygyro
);
88 _mav_put_float(buf
, 28, zgyro
);
89 _mav_put_float(buf
, 32, xmag
);
90 _mav_put_float(buf
, 36, ymag
);
91 _mav_put_float(buf
, 40, zmag
);
92 _mav_put_float(buf
, 44, abs_pressure
);
93 _mav_put_float(buf
, 48, diff_pressure
);
94 _mav_put_float(buf
, 52, pressure_alt
);
95 _mav_put_float(buf
, 56, temperature
);
96 _mav_put_uint16_t(buf
, 60, fields_updated
);
98 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
100 mavlink_highres_imu_t packet
;
101 packet
.time_usec
= time_usec
;
105 packet
.xgyro
= xgyro
;
106 packet
.ygyro
= ygyro
;
107 packet
.zgyro
= zgyro
;
111 packet
.abs_pressure
= abs_pressure
;
112 packet
.diff_pressure
= diff_pressure
;
113 packet
.pressure_alt
= pressure_alt
;
114 packet
.temperature
= temperature
;
115 packet
.fields_updated
= fields_updated
;
117 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
120 msg
->msgid
= MAVLINK_MSG_ID_HIGHRES_IMU
;
121 #if MAVLINK_CRC_EXTRA
122 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
124 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
129 * @brief Pack a highres_imu message on a channel
130 * @param system_id ID of this system
131 * @param component_id ID of this component (e.g. 200 for IMU)
132 * @param chan The MAVLink channel this message will be sent over
133 * @param msg The MAVLink message to compress the data into
134 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
135 * @param xacc X acceleration (m/s^2)
136 * @param yacc Y acceleration (m/s^2)
137 * @param zacc Z acceleration (m/s^2)
138 * @param xgyro Angular speed around X axis (rad / sec)
139 * @param ygyro Angular speed around Y axis (rad / sec)
140 * @param zgyro Angular speed around Z axis (rad / sec)
141 * @param xmag X Magnetic field (Gauss)
142 * @param ymag Y Magnetic field (Gauss)
143 * @param zmag Z Magnetic field (Gauss)
144 * @param abs_pressure Absolute pressure in millibar
145 * @param diff_pressure Differential pressure in millibar
146 * @param pressure_alt Altitude calculated from pressure
147 * @param temperature Temperature in degrees celsius
148 * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
149 * @return length of the message in bytes (excluding serial stream start sign)
151 static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
152 mavlink_message_t
* msg
,
153 uint64_t time_usec
,float xacc
,float yacc
,float zacc
,float xgyro
,float ygyro
,float zgyro
,float xmag
,float ymag
,float zmag
,float abs_pressure
,float diff_pressure
,float pressure_alt
,float temperature
,uint16_t fields_updated
)
155 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
156 char buf
[MAVLINK_MSG_ID_HIGHRES_IMU_LEN
];
157 _mav_put_uint64_t(buf
, 0, time_usec
);
158 _mav_put_float(buf
, 8, xacc
);
159 _mav_put_float(buf
, 12, yacc
);
160 _mav_put_float(buf
, 16, zacc
);
161 _mav_put_float(buf
, 20, xgyro
);
162 _mav_put_float(buf
, 24, ygyro
);
163 _mav_put_float(buf
, 28, zgyro
);
164 _mav_put_float(buf
, 32, xmag
);
165 _mav_put_float(buf
, 36, ymag
);
166 _mav_put_float(buf
, 40, zmag
);
167 _mav_put_float(buf
, 44, abs_pressure
);
168 _mav_put_float(buf
, 48, diff_pressure
);
169 _mav_put_float(buf
, 52, pressure_alt
);
170 _mav_put_float(buf
, 56, temperature
);
171 _mav_put_uint16_t(buf
, 60, fields_updated
);
173 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
175 mavlink_highres_imu_t packet
;
176 packet
.time_usec
= time_usec
;
180 packet
.xgyro
= xgyro
;
181 packet
.ygyro
= ygyro
;
182 packet
.zgyro
= zgyro
;
186 packet
.abs_pressure
= abs_pressure
;
187 packet
.diff_pressure
= diff_pressure
;
188 packet
.pressure_alt
= pressure_alt
;
189 packet
.temperature
= temperature
;
190 packet
.fields_updated
= fields_updated
;
192 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
195 msg
->msgid
= MAVLINK_MSG_ID_HIGHRES_IMU
;
196 #if MAVLINK_CRC_EXTRA
197 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
199 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
204 * @brief Encode a highres_imu struct
206 * @param system_id ID of this system
207 * @param component_id ID of this component (e.g. 200 for IMU)
208 * @param msg The MAVLink message to compress the data into
209 * @param highres_imu C-struct to read the message contents from
211 static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_highres_imu_t
* highres_imu
)
213 return mavlink_msg_highres_imu_pack(system_id
, component_id
, msg
, highres_imu
->time_usec
, highres_imu
->xacc
, highres_imu
->yacc
, highres_imu
->zacc
, highres_imu
->xgyro
, highres_imu
->ygyro
, highres_imu
->zgyro
, highres_imu
->xmag
, highres_imu
->ymag
, highres_imu
->zmag
, highres_imu
->abs_pressure
, highres_imu
->diff_pressure
, highres_imu
->pressure_alt
, highres_imu
->temperature
, highres_imu
->fields_updated
);
217 * @brief Encode a highres_imu struct on a channel
219 * @param system_id ID of this system
220 * @param component_id ID of this component (e.g. 200 for IMU)
221 * @param chan The MAVLink channel this message will be sent over
222 * @param msg The MAVLink message to compress the data into
223 * @param highres_imu C-struct to read the message contents from
225 static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_highres_imu_t
* highres_imu
)
227 return mavlink_msg_highres_imu_pack_chan(system_id
, component_id
, chan
, msg
, highres_imu
->time_usec
, highres_imu
->xacc
, highres_imu
->yacc
, highres_imu
->zacc
, highres_imu
->xgyro
, highres_imu
->ygyro
, highres_imu
->zgyro
, highres_imu
->xmag
, highres_imu
->ymag
, highres_imu
->zmag
, highres_imu
->abs_pressure
, highres_imu
->diff_pressure
, highres_imu
->pressure_alt
, highres_imu
->temperature
, highres_imu
->fields_updated
);
231 * @brief Send a highres_imu message
232 * @param chan MAVLink channel to send the message
234 * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
235 * @param xacc X acceleration (m/s^2)
236 * @param yacc Y acceleration (m/s^2)
237 * @param zacc Z acceleration (m/s^2)
238 * @param xgyro Angular speed around X axis (rad / sec)
239 * @param ygyro Angular speed around Y axis (rad / sec)
240 * @param zgyro Angular speed around Z axis (rad / sec)
241 * @param xmag X Magnetic field (Gauss)
242 * @param ymag Y Magnetic field (Gauss)
243 * @param zmag Z Magnetic field (Gauss)
244 * @param abs_pressure Absolute pressure in millibar
245 * @param diff_pressure Differential pressure in millibar
246 * @param pressure_alt Altitude calculated from pressure
247 * @param temperature Temperature in degrees celsius
248 * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
250 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
252 static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan
, uint64_t time_usec
, float xacc
, float yacc
, float zacc
, float xgyro
, float ygyro
, float zgyro
, float xmag
, float ymag
, float zmag
, float abs_pressure
, float diff_pressure
, float pressure_alt
, float temperature
, uint16_t fields_updated
)
254 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
255 char buf
[MAVLINK_MSG_ID_HIGHRES_IMU_LEN
];
256 _mav_put_uint64_t(buf
, 0, time_usec
);
257 _mav_put_float(buf
, 8, xacc
);
258 _mav_put_float(buf
, 12, yacc
);
259 _mav_put_float(buf
, 16, zacc
);
260 _mav_put_float(buf
, 20, xgyro
);
261 _mav_put_float(buf
, 24, ygyro
);
262 _mav_put_float(buf
, 28, zgyro
);
263 _mav_put_float(buf
, 32, xmag
);
264 _mav_put_float(buf
, 36, ymag
);
265 _mav_put_float(buf
, 40, zmag
);
266 _mav_put_float(buf
, 44, abs_pressure
);
267 _mav_put_float(buf
, 48, diff_pressure
);
268 _mav_put_float(buf
, 52, pressure_alt
);
269 _mav_put_float(buf
, 56, temperature
);
270 _mav_put_uint16_t(buf
, 60, fields_updated
);
272 #if MAVLINK_CRC_EXTRA
273 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
275 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
278 mavlink_highres_imu_t packet
;
279 packet
.time_usec
= time_usec
;
283 packet
.xgyro
= xgyro
;
284 packet
.ygyro
= ygyro
;
285 packet
.zgyro
= zgyro
;
289 packet
.abs_pressure
= abs_pressure
;
290 packet
.diff_pressure
= diff_pressure
;
291 packet
.pressure_alt
= pressure_alt
;
292 packet
.temperature
= temperature
;
293 packet
.fields_updated
= fields_updated
;
295 #if MAVLINK_CRC_EXTRA
296 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, (const char *)&packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
298 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, (const char *)&packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
303 #if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
305 This varient of _send() can be used to save stack space by re-using
306 memory from the receive buffer. The caller provides a
307 mavlink_message_t which is the size of a full mavlink message. This
308 is usually the receive buffer for the channel, and allows a reply to an
309 incoming message with minimum stack space usage.
311 static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, float xacc
, float yacc
, float zacc
, float xgyro
, float ygyro
, float zgyro
, float xmag
, float ymag
, float zmag
, float abs_pressure
, float diff_pressure
, float pressure_alt
, float temperature
, uint16_t fields_updated
)
313 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
314 char *buf
= (char *)msgbuf
;
315 _mav_put_uint64_t(buf
, 0, time_usec
);
316 _mav_put_float(buf
, 8, xacc
);
317 _mav_put_float(buf
, 12, yacc
);
318 _mav_put_float(buf
, 16, zacc
);
319 _mav_put_float(buf
, 20, xgyro
);
320 _mav_put_float(buf
, 24, ygyro
);
321 _mav_put_float(buf
, 28, zgyro
);
322 _mav_put_float(buf
, 32, xmag
);
323 _mav_put_float(buf
, 36, ymag
);
324 _mav_put_float(buf
, 40, zmag
);
325 _mav_put_float(buf
, 44, abs_pressure
);
326 _mav_put_float(buf
, 48, diff_pressure
);
327 _mav_put_float(buf
, 52, pressure_alt
);
328 _mav_put_float(buf
, 56, temperature
);
329 _mav_put_uint16_t(buf
, 60, fields_updated
);
331 #if MAVLINK_CRC_EXTRA
332 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
334 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, buf
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
337 mavlink_highres_imu_t
*packet
= (mavlink_highres_imu_t
*)msgbuf
;
338 packet
->time_usec
= time_usec
;
342 packet
->xgyro
= xgyro
;
343 packet
->ygyro
= ygyro
;
344 packet
->zgyro
= zgyro
;
348 packet
->abs_pressure
= abs_pressure
;
349 packet
->diff_pressure
= diff_pressure
;
350 packet
->pressure_alt
= pressure_alt
;
351 packet
->temperature
= temperature
;
352 packet
->fields_updated
= fields_updated
;
354 #if MAVLINK_CRC_EXTRA
355 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, (const char *)packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
, MAVLINK_MSG_ID_HIGHRES_IMU_CRC
);
357 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_HIGHRES_IMU
, (const char *)packet
, MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);
365 // MESSAGE HIGHRES_IMU UNPACKING
369 * @brief Get field time_usec from highres_imu message
371 * @return Timestamp (microseconds, synced to UNIX time or since system boot)
373 static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t
* msg
)
375 return _MAV_RETURN_uint64_t(msg
, 0);
379 * @brief Get field xacc from highres_imu message
381 * @return X acceleration (m/s^2)
383 static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t
* msg
)
385 return _MAV_RETURN_float(msg
, 8);
389 * @brief Get field yacc from highres_imu message
391 * @return Y acceleration (m/s^2)
393 static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t
* msg
)
395 return _MAV_RETURN_float(msg
, 12);
399 * @brief Get field zacc from highres_imu message
401 * @return Z acceleration (m/s^2)
403 static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_float(msg
, 16);
409 * @brief Get field xgyro from highres_imu message
411 * @return Angular speed around X axis (rad / sec)
413 static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_float(msg
, 20);
419 * @brief Get field ygyro from highres_imu message
421 * @return Angular speed around Y axis (rad / sec)
423 static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_float(msg
, 24);
429 * @brief Get field zgyro from highres_imu message
431 * @return Angular speed around Z axis (rad / sec)
433 static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_float(msg
, 28);
439 * @brief Get field xmag from highres_imu message
441 * @return X Magnetic field (Gauss)
443 static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t
* msg
)
445 return _MAV_RETURN_float(msg
, 32);
449 * @brief Get field ymag from highres_imu message
451 * @return Y Magnetic field (Gauss)
453 static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t
* msg
)
455 return _MAV_RETURN_float(msg
, 36);
459 * @brief Get field zmag from highres_imu message
461 * @return Z Magnetic field (Gauss)
463 static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t
* msg
)
465 return _MAV_RETURN_float(msg
, 40);
469 * @brief Get field abs_pressure from highres_imu message
471 * @return Absolute pressure in millibar
473 static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t
* msg
)
475 return _MAV_RETURN_float(msg
, 44);
479 * @brief Get field diff_pressure from highres_imu message
481 * @return Differential pressure in millibar
483 static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t
* msg
)
485 return _MAV_RETURN_float(msg
, 48);
489 * @brief Get field pressure_alt from highres_imu message
491 * @return Altitude calculated from pressure
493 static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t
* msg
)
495 return _MAV_RETURN_float(msg
, 52);
499 * @brief Get field temperature from highres_imu message
501 * @return Temperature in degrees celsius
503 static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t
* msg
)
505 return _MAV_RETURN_float(msg
, 56);
509 * @brief Get field fields_updated from highres_imu message
511 * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
513 static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t
* msg
)
515 return _MAV_RETURN_uint16_t(msg
, 60);
519 * @brief Decode a highres_imu message into a struct
521 * @param msg The message to decode
522 * @param highres_imu C-struct to decode the message contents into
524 static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t
* msg
, mavlink_highres_imu_t
* highres_imu
)
526 #if MAVLINK_NEED_BYTE_SWAP
527 highres_imu
->time_usec
= mavlink_msg_highres_imu_get_time_usec(msg
);
528 highres_imu
->xacc
= mavlink_msg_highres_imu_get_xacc(msg
);
529 highres_imu
->yacc
= mavlink_msg_highres_imu_get_yacc(msg
);
530 highres_imu
->zacc
= mavlink_msg_highres_imu_get_zacc(msg
);
531 highres_imu
->xgyro
= mavlink_msg_highres_imu_get_xgyro(msg
);
532 highres_imu
->ygyro
= mavlink_msg_highres_imu_get_ygyro(msg
);
533 highres_imu
->zgyro
= mavlink_msg_highres_imu_get_zgyro(msg
);
534 highres_imu
->xmag
= mavlink_msg_highres_imu_get_xmag(msg
);
535 highres_imu
->ymag
= mavlink_msg_highres_imu_get_ymag(msg
);
536 highres_imu
->zmag
= mavlink_msg_highres_imu_get_zmag(msg
);
537 highres_imu
->abs_pressure
= mavlink_msg_highres_imu_get_abs_pressure(msg
);
538 highres_imu
->diff_pressure
= mavlink_msg_highres_imu_get_diff_pressure(msg
);
539 highres_imu
->pressure_alt
= mavlink_msg_highres_imu_get_pressure_alt(msg
);
540 highres_imu
->temperature
= mavlink_msg_highres_imu_get_temperature(msg
);
541 highres_imu
->fields_updated
= mavlink_msg_highres_imu_get_fields_updated(msg
);
543 memcpy(highres_imu
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_HIGHRES_IMU_LEN
);