mavlink_msg_small_imu.h
Go to the documentation of this file.
1 // MESSAGE SMALL_IMU PACKING
2 
3 #define MAVLINK_MSG_ID_SMALL_IMU 181
4 
5 typedef struct __mavlink_small_imu_t
6 {
7  uint64_t time_boot_us; /*< Measurement timestamp as microseconds since boot*/
8  float xacc; /*< Acceleration along X axis*/
9  float yacc; /*< Acceleration along Y axis*/
10  float zacc; /*< Acceleration along Z axis*/
11  float xgyro; /*< Angular speed around X axis*/
12  float ygyro; /*< Angular speed around Y axis*/
13  float zgyro; /*< Angular speed around Z axis*/
14  float temperature; /*< Internal temperature measurement*/
16 
17 #define MAVLINK_MSG_ID_SMALL_IMU_LEN 36
18 #define MAVLINK_MSG_ID_181_LEN 36
19 
20 #define MAVLINK_MSG_ID_SMALL_IMU_CRC 67
21 #define MAVLINK_MSG_ID_181_CRC 67
22 
23 
24 
25 #define MAVLINK_MESSAGE_INFO_SMALL_IMU { \
26  "SMALL_IMU", \
27  8, \
28  { { "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_small_imu_t, time_boot_us) }, \
29  { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_small_imu_t, xacc) }, \
30  { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_small_imu_t, yacc) }, \
31  { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_small_imu_t, zacc) }, \
32  { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_small_imu_t, xgyro) }, \
33  { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_small_imu_t, ygyro) }, \
34  { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_small_imu_t, zgyro) }, \
35  { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_small_imu_t, temperature) }, \
36  } \
37 }
38 
39 
56 static inline uint16_t mavlink_msg_small_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57  uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature)
58 {
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
61  _mav_put_uint64_t(buf, 0, time_boot_us);
62  _mav_put_float(buf, 8, xacc);
63  _mav_put_float(buf, 12, yacc);
64  _mav_put_float(buf, 16, zacc);
65  _mav_put_float(buf, 20, xgyro);
66  _mav_put_float(buf, 24, ygyro);
67  _mav_put_float(buf, 28, zgyro);
68  _mav_put_float(buf, 32, temperature);
69 
71 #else
72  mavlink_small_imu_t packet;
73  packet.time_boot_us = time_boot_us;
74  packet.xacc = xacc;
75  packet.yacc = yacc;
76  packet.zacc = zacc;
77  packet.xgyro = xgyro;
78  packet.ygyro = ygyro;
79  packet.zgyro = zgyro;
80  packet.temperature = temperature;
81 
83 #endif
84 
85  msg->msgid = MAVLINK_MSG_ID_SMALL_IMU;
86 #if MAVLINK_CRC_EXTRA
88 #else
89  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SMALL_IMU_LEN);
90 #endif
91 }
92 
109 static inline uint16_t mavlink_msg_small_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110  mavlink_message_t* msg,
111  uint64_t time_boot_us,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float temperature)
112 {
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115  _mav_put_uint64_t(buf, 0, time_boot_us);
116  _mav_put_float(buf, 8, xacc);
117  _mav_put_float(buf, 12, yacc);
118  _mav_put_float(buf, 16, zacc);
119  _mav_put_float(buf, 20, xgyro);
120  _mav_put_float(buf, 24, ygyro);
121  _mav_put_float(buf, 28, zgyro);
122  _mav_put_float(buf, 32, temperature);
123 
125 #else
126  mavlink_small_imu_t packet;
127  packet.time_boot_us = time_boot_us;
128  packet.xacc = xacc;
129  packet.yacc = yacc;
130  packet.zacc = zacc;
131  packet.xgyro = xgyro;
132  packet.ygyro = ygyro;
133  packet.zgyro = zgyro;
134  packet.temperature = temperature;
135 
137 #endif
138 
139  msg->msgid = MAVLINK_MSG_ID_SMALL_IMU;
140 #if MAVLINK_CRC_EXTRA
142 #else
143  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SMALL_IMU_LEN);
144 #endif
145 }
146 
155 static inline uint16_t mavlink_msg_small_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu)
156 {
157  return mavlink_msg_small_imu_pack(system_id, component_id, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature);
158 }
159 
169 static inline uint16_t mavlink_msg_small_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_small_imu_t* small_imu)
170 {
171  return mavlink_msg_small_imu_pack_chan(system_id, component_id, chan, msg, small_imu->time_boot_us, small_imu->xacc, small_imu->yacc, small_imu->zacc, small_imu->xgyro, small_imu->ygyro, small_imu->zgyro, small_imu->temperature);
172 }
173 
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
188 
189 static inline void mavlink_msg_small_imu_send(mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature)
190 {
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
194  _mav_put_float(buf, 8, xacc);
195  _mav_put_float(buf, 12, yacc);
196  _mav_put_float(buf, 16, zacc);
197  _mav_put_float(buf, 20, xgyro);
198  _mav_put_float(buf, 24, ygyro);
199  _mav_put_float(buf, 28, zgyro);
200  _mav_put_float(buf, 32, temperature);
201 
202 #if MAVLINK_CRC_EXTRA
203  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC);
204 #else
205  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN);
206 #endif
207 #else
208  mavlink_small_imu_t packet;
209  packet.time_boot_us = time_boot_us;
210  packet.xacc = xacc;
211  packet.yacc = yacc;
212  packet.zacc = zacc;
213  packet.xgyro = xgyro;
214  packet.ygyro = ygyro;
215  packet.zgyro = zgyro;
216  packet.temperature = temperature;
217 
218 #if MAVLINK_CRC_EXTRA
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC);
220 #else
221  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)&packet, MAVLINK_MSG_ID_SMALL_IMU_LEN);
222 #endif
223 #endif
224 }
225 
226 #if MAVLINK_MSG_ID_SMALL_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227 /*
228  This varient of _send() can be used to save stack space by re-using
229  memory from the receive buffer. The caller provides a
230  mavlink_message_t which is the size of a full mavlink message. This
231  is usually the receive buffer for the channel, and allows a reply to an
232  incoming message with minimum stack space usage.
233  */
234 static inline void mavlink_msg_small_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_boot_us, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float temperature)
235 {
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237  char *buf = (char *)msgbuf;
239  _mav_put_float(buf, 8, xacc);
240  _mav_put_float(buf, 12, yacc);
241  _mav_put_float(buf, 16, zacc);
242  _mav_put_float(buf, 20, xgyro);
243  _mav_put_float(buf, 24, ygyro);
244  _mav_put_float(buf, 28, zgyro);
245  _mav_put_float(buf, 32, temperature);
246 
247 #if MAVLINK_CRC_EXTRA
248  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC);
249 #else
250  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, buf, MAVLINK_MSG_ID_SMALL_IMU_LEN);
251 #endif
252 #else
253  mavlink_small_imu_t *packet = (mavlink_small_imu_t *)msgbuf;
254  packet->time_boot_us = time_boot_us;
255  packet->xacc = xacc;
256  packet->yacc = yacc;
257  packet->zacc = zacc;
258  packet->xgyro = xgyro;
259  packet->ygyro = ygyro;
260  packet->zgyro = zgyro;
261  packet->temperature = temperature;
262 
263 #if MAVLINK_CRC_EXTRA
264  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN, MAVLINK_MSG_ID_SMALL_IMU_CRC);
265 #else
266  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SMALL_IMU, (const char *)packet, MAVLINK_MSG_ID_SMALL_IMU_LEN);
267 #endif
268 #endif
269 }
270 #endif
271 
272 #endif
273 
274 // MESSAGE SMALL_IMU UNPACKING
275 
276 
282 static inline uint64_t mavlink_msg_small_imu_get_time_boot_us(const mavlink_message_t* msg)
283 {
284  return _MAV_RETURN_uint64_t(msg, 0);
285 }
286 
292 static inline float mavlink_msg_small_imu_get_xacc(const mavlink_message_t* msg)
293 {
294  return _MAV_RETURN_float(msg, 8);
295 }
296 
302 static inline float mavlink_msg_small_imu_get_yacc(const mavlink_message_t* msg)
303 {
304  return _MAV_RETURN_float(msg, 12);
305 }
306 
312 static inline float mavlink_msg_small_imu_get_zacc(const mavlink_message_t* msg)
313 {
314  return _MAV_RETURN_float(msg, 16);
315 }
316 
322 static inline float mavlink_msg_small_imu_get_xgyro(const mavlink_message_t* msg)
323 {
324  return _MAV_RETURN_float(msg, 20);
325 }
326 
332 static inline float mavlink_msg_small_imu_get_ygyro(const mavlink_message_t* msg)
333 {
334  return _MAV_RETURN_float(msg, 24);
335 }
336 
342 static inline float mavlink_msg_small_imu_get_zgyro(const mavlink_message_t* msg)
343 {
344  return _MAV_RETURN_float(msg, 28);
345 }
346 
352 static inline float mavlink_msg_small_imu_get_temperature(const mavlink_message_t* msg)
353 {
354  return _MAV_RETURN_float(msg, 32);
355 }
356 
363 static inline void mavlink_msg_small_imu_decode(const mavlink_message_t* msg, mavlink_small_imu_t* small_imu)
364 {
365 #if MAVLINK_NEED_BYTE_SWAP
367  small_imu->xacc = mavlink_msg_small_imu_get_xacc(msg);
368  small_imu->yacc = mavlink_msg_small_imu_get_yacc(msg);
369  small_imu->zacc = mavlink_msg_small_imu_get_zacc(msg);
370  small_imu->xgyro = mavlink_msg_small_imu_get_xgyro(msg);
371  small_imu->ygyro = mavlink_msg_small_imu_get_ygyro(msg);
372  small_imu->zgyro = mavlink_msg_small_imu_get_zgyro(msg);
374 #else
375  memcpy(small_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SMALL_IMU_LEN);
376 #endif
377 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47