Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE SCALED_IMU PACKING
2
 
3
#define MAVLINK_MSG_ID_SCALED_IMU 26
4
 
5
typedef struct __mavlink_scaled_imu_t
6
{
7
 uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
8
 int16_t xacc; ///< X acceleration (mg)
9
 int16_t yacc; ///< Y acceleration (mg)
10
 int16_t zacc; ///< Z acceleration (mg)
11
 int16_t xgyro; ///< Angular speed around X axis (millirad /sec)
12
 int16_t ygyro; ///< Angular speed around Y axis (millirad /sec)
13
 int16_t zgyro; ///< Angular speed around Z axis (millirad /sec)
14
 int16_t xmag; ///< X Magnetic field (milli tesla)
15
 int16_t ymag; ///< Y Magnetic field (milli tesla)
16
 int16_t zmag; ///< Z Magnetic field (milli tesla)
17
} mavlink_scaled_imu_t;
18
 
19
#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22
20
#define MAVLINK_MSG_ID_26_LEN 22
21
 
22
 
23
 
24
#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
25
        "SCALED_IMU", \
26
        10, \
27
        {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \
28
         { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \
29
         { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \
30
         { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \
31
         { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \
32
         { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \
33
         { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \
34
         { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \
35
         { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \
36
         { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \
37
         } \
38
}
39
 
40
 
41
/**
42
 * @brief Pack a scaled_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
46
 *
47
 * @param time_boot_ms Timestamp (milliseconds since system boot)
48
 * @param xacc X acceleration (mg)
49
 * @param yacc Y acceleration (mg)
50
 * @param zacc Z acceleration (mg)
51
 * @param xgyro Angular speed around X axis (millirad /sec)
52
 * @param ygyro Angular speed around Y axis (millirad /sec)
53
 * @param zgyro Angular speed around Z axis (millirad /sec)
54
 * @param xmag X Magnetic field (milli tesla)
55
 * @param ymag Y Magnetic field (milli tesla)
56
 * @param zmag Z Magnetic field (milli tesla)
57
 * @return length of the message in bytes (excluding serial stream start sign)
58
 */
59
static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
60
                                                       uint32_t time_boot_ms, 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)
61
{
62
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63
        char buf[22];
64
        _mav_put_uint32_t(buf, 0, time_boot_ms);
65
        _mav_put_int16_t(buf, 4, xacc);
66
        _mav_put_int16_t(buf, 6, yacc);
67
        _mav_put_int16_t(buf, 8, zacc);
68
        _mav_put_int16_t(buf, 10, xgyro);
69
        _mav_put_int16_t(buf, 12, ygyro);
70
        _mav_put_int16_t(buf, 14, zgyro);
71
        _mav_put_int16_t(buf, 16, xmag);
72
        _mav_put_int16_t(buf, 18, ymag);
73
        _mav_put_int16_t(buf, 20, zmag);
74
 
75
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
76
#else
77
        mavlink_scaled_imu_t packet;
78
        packet.time_boot_ms = time_boot_ms;
79
        packet.xacc = xacc;
80
        packet.yacc = yacc;
81
        packet.zacc = zacc;
82
        packet.xgyro = xgyro;
83
        packet.ygyro = ygyro;
84
        packet.zgyro = zgyro;
85
        packet.xmag = xmag;
86
        packet.ymag = ymag;
87
        packet.zmag = zmag;
88
 
89
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
90
#endif
91
 
92
        msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
93
        return mavlink_finalize_message(msg, system_id, component_id, 22, 170);
94
}
95
 
96
/**
97
 * @brief Pack a scaled_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_boot_ms Timestamp (milliseconds since system boot)
103
 * @param xacc X acceleration (mg)
104
 * @param yacc Y acceleration (mg)
105
 * @param zacc Z acceleration (mg)
106
 * @param xgyro Angular speed around X axis (millirad /sec)
107
 * @param ygyro Angular speed around Y axis (millirad /sec)
108
 * @param zgyro Angular speed around Z axis (millirad /sec)
109
 * @param xmag X Magnetic field (milli tesla)
110
 * @param ymag Y Magnetic field (milli tesla)
111
 * @param zmag Z Magnetic field (milli tesla)
112
 * @return length of the message in bytes (excluding serial stream start sign)
113
 */
114
static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
115
                                                           mavlink_message_t* msg,
116
                                                           uint32_t time_boot_ms,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)
117
{
118
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
119
        char buf[22];
120
        _mav_put_uint32_t(buf, 0, time_boot_ms);
121
        _mav_put_int16_t(buf, 4, xacc);
122
        _mav_put_int16_t(buf, 6, yacc);
123
        _mav_put_int16_t(buf, 8, zacc);
124
        _mav_put_int16_t(buf, 10, xgyro);
125
        _mav_put_int16_t(buf, 12, ygyro);
126
        _mav_put_int16_t(buf, 14, zgyro);
127
        _mav_put_int16_t(buf, 16, xmag);
128
        _mav_put_int16_t(buf, 18, ymag);
129
        _mav_put_int16_t(buf, 20, zmag);
130
 
131
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
132
#else
133
        mavlink_scaled_imu_t packet;
134
        packet.time_boot_ms = time_boot_ms;
135
        packet.xacc = xacc;
136
        packet.yacc = yacc;
137
        packet.zacc = zacc;
138
        packet.xgyro = xgyro;
139
        packet.ygyro = ygyro;
140
        packet.zgyro = zgyro;
141
        packet.xmag = xmag;
142
        packet.ymag = ymag;
143
        packet.zmag = zmag;
144
 
145
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
146
#endif
147
 
148
        msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
149
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 170);
150
}
151
 
152
/**
153
 * @brief Encode a scaled_imu struct into a message
154
 *
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 scaled_imu C-struct to read the message contents from
159
 */
160
static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
161
{
162
        return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
163
}
164
 
165
/**
166
 * @brief Send a scaled_imu message
167
 * @param chan MAVLink channel to send the message
168
 *
169
 * @param time_boot_ms Timestamp (milliseconds since system boot)
170
 * @param xacc X acceleration (mg)
171
 * @param yacc Y acceleration (mg)
172
 * @param zacc Z acceleration (mg)
173
 * @param xgyro Angular speed around X axis (millirad /sec)
174
 * @param ygyro Angular speed around Y axis (millirad /sec)
175
 * @param zgyro Angular speed around Z axis (millirad /sec)
176
 * @param xmag X Magnetic field (milli tesla)
177
 * @param ymag Y Magnetic field (milli tesla)
178
 * @param zmag Z Magnetic field (milli tesla)
179
 */
180
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
181
 
182
static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, 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)
183
{
184
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
185
        char buf[22];
186
        _mav_put_uint32_t(buf, 0, time_boot_ms);
187
        _mav_put_int16_t(buf, 4, xacc);
188
        _mav_put_int16_t(buf, 6, yacc);
189
        _mav_put_int16_t(buf, 8, zacc);
190
        _mav_put_int16_t(buf, 10, xgyro);
191
        _mav_put_int16_t(buf, 12, ygyro);
192
        _mav_put_int16_t(buf, 14, zgyro);
193
        _mav_put_int16_t(buf, 16, xmag);
194
        _mav_put_int16_t(buf, 18, ymag);
195
        _mav_put_int16_t(buf, 20, zmag);
196
 
197
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 22, 170);
198
#else
199
        mavlink_scaled_imu_t packet;
200
        packet.time_boot_ms = time_boot_ms;
201
        packet.xacc = xacc;
202
        packet.yacc = yacc;
203
        packet.zacc = zacc;
204
        packet.xgyro = xgyro;
205
        packet.ygyro = ygyro;
206
        packet.zgyro = zgyro;
207
        packet.xmag = xmag;
208
        packet.ymag = ymag;
209
        packet.zmag = zmag;
210
 
211
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 22, 170);
212
#endif
213
}
214
 
215
#endif
216
 
217
// MESSAGE SCALED_IMU UNPACKING
218
 
219
 
220
/**
221
 * @brief Get field time_boot_ms from scaled_imu message
222
 *
223
 * @return Timestamp (milliseconds since system boot)
224
 */
225
static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg)
226
{
227
        return _MAV_RETURN_uint32_t(msg,  0);
228
}
229
 
230
/**
231
 * @brief Get field xacc from scaled_imu message
232
 *
233
 * @return X acceleration (mg)
234
 */
235
static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg)
236
{
237
        return _MAV_RETURN_int16_t(msg,  4);
238
}
239
 
240
/**
241
 * @brief Get field yacc from scaled_imu message
242
 *
243
 * @return Y acceleration (mg)
244
 */
245
static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg)
246
{
247
        return _MAV_RETURN_int16_t(msg,  6);
248
}
249
 
250
/**
251
 * @brief Get field zacc from scaled_imu message
252
 *
253
 * @return Z acceleration (mg)
254
 */
255
static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg)
256
{
257
        return _MAV_RETURN_int16_t(msg,  8);
258
}
259
 
260
/**
261
 * @brief Get field xgyro from scaled_imu message
262
 *
263
 * @return Angular speed around X axis (millirad /sec)
264
 */
265
static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg)
266
{
267
        return _MAV_RETURN_int16_t(msg,  10);
268
}
269
 
270
/**
271
 * @brief Get field ygyro from scaled_imu message
272
 *
273
 * @return Angular speed around Y axis (millirad /sec)
274
 */
275
static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg)
276
{
277
        return _MAV_RETURN_int16_t(msg,  12);
278
}
279
 
280
/**
281
 * @brief Get field zgyro from scaled_imu message
282
 *
283
 * @return Angular speed around Z axis (millirad /sec)
284
 */
285
static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg)
286
{
287
        return _MAV_RETURN_int16_t(msg,  14);
288
}
289
 
290
/**
291
 * @brief Get field xmag from scaled_imu message
292
 *
293
 * @return X Magnetic field (milli tesla)
294
 */
295
static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg)
296
{
297
        return _MAV_RETURN_int16_t(msg,  16);
298
}
299
 
300
/**
301
 * @brief Get field ymag from scaled_imu message
302
 *
303
 * @return Y Magnetic field (milli tesla)
304
 */
305
static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg)
306
{
307
        return _MAV_RETURN_int16_t(msg,  18);
308
}
309
 
310
/**
311
 * @brief Get field zmag from scaled_imu message
312
 *
313
 * @return Z Magnetic field (milli tesla)
314
 */
315
static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg)
316
{
317
        return _MAV_RETURN_int16_t(msg,  20);
318
}
319
 
320
/**
321
 * @brief Decode a scaled_imu message into a struct
322
 *
323
 * @param msg The message to decode
324
 * @param scaled_imu C-struct to decode the message contents into
325
 */
326
static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu)
327
{
328
#if MAVLINK_NEED_BYTE_SWAP
329
        scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg);
330
        scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg);
331
        scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg);
332
        scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg);
333
        scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
334
        scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
335
        scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
336
        scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg);
337
        scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg);
338
        scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg);
339
#else
340
        memcpy(scaled_imu, _MAV_PAYLOAD(msg), 22);
341
#endif
342
}