tarask
6 days ago 532005c6573d95199ce0ffbc33df4c7a0a4c3ef9
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
#pragma once
// MESSAGE VIBRATION PACKING
 
#define MAVLINK_MSG_ID_VIBRATION 241
 
 
typedef struct __mavlink_vibration_t {
 uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
 float vibration_x; /*<  Vibration levels on X-axis*/
 float vibration_y; /*<  Vibration levels on Y-axis*/
 float vibration_z; /*<  Vibration levels on Z-axis*/
 uint32_t clipping_0; /*<  first accelerometer clipping count*/
 uint32_t clipping_1; /*<  second accelerometer clipping count*/
 uint32_t clipping_2; /*<  third accelerometer clipping count*/
} mavlink_vibration_t;
 
#define MAVLINK_MSG_ID_VIBRATION_LEN 32
#define MAVLINK_MSG_ID_VIBRATION_MIN_LEN 32
#define MAVLINK_MSG_ID_241_LEN 32
#define MAVLINK_MSG_ID_241_MIN_LEN 32
 
#define MAVLINK_MSG_ID_VIBRATION_CRC 90
#define MAVLINK_MSG_ID_241_CRC 90
 
 
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_VIBRATION { \
    241, \
    "VIBRATION", \
    7, \
    {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \
         { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \
         { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \
         { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \
         { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \
         { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \
         { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_VIBRATION { \
    "VIBRATION", \
    7, \
    {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vibration_t, time_usec) }, \
         { "vibration_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vibration_t, vibration_x) }, \
         { "vibration_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vibration_t, vibration_y) }, \
         { "vibration_z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vibration_t, vibration_z) }, \
         { "clipping_0", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_vibration_t, clipping_0) }, \
         { "clipping_1", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_vibration_t, clipping_1) }, \
         { "clipping_2", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_vibration_t, clipping_2) }, \
         } \
}
#endif
 
/**
 * @brief Pack a vibration message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
 * @param vibration_x  Vibration levels on X-axis
 * @param vibration_y  Vibration levels on Y-axis
 * @param vibration_z  Vibration levels on Z-axis
 * @param clipping_0  first accelerometer clipping count
 * @param clipping_1  second accelerometer clipping count
 * @param clipping_2  third accelerometer clipping count
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_vibration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
    _mav_put_uint64_t(buf, 0, time_usec);
    _mav_put_float(buf, 8, vibration_x);
    _mav_put_float(buf, 12, vibration_y);
    _mav_put_float(buf, 16, vibration_z);
    _mav_put_uint32_t(buf, 20, clipping_0);
    _mav_put_uint32_t(buf, 24, clipping_1);
    _mav_put_uint32_t(buf, 28, clipping_2);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN);
#else
    mavlink_vibration_t packet;
    packet.time_usec = time_usec;
    packet.vibration_x = vibration_x;
    packet.vibration_y = vibration_y;
    packet.vibration_z = vibration_z;
    packet.clipping_0 = clipping_0;
    packet.clipping_1 = clipping_1;
    packet.clipping_2 = clipping_2;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_VIBRATION;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
}
 
/**
 * @brief Pack a vibration message on a channel
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
 * @param vibration_x  Vibration levels on X-axis
 * @param vibration_y  Vibration levels on Y-axis
 * @param vibration_z  Vibration levels on Z-axis
 * @param clipping_0  first accelerometer clipping count
 * @param clipping_1  second accelerometer clipping count
 * @param clipping_2  third accelerometer clipping count
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_vibration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   uint64_t time_usec,float vibration_x,float vibration_y,float vibration_z,uint32_t clipping_0,uint32_t clipping_1,uint32_t clipping_2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
    _mav_put_uint64_t(buf, 0, time_usec);
    _mav_put_float(buf, 8, vibration_x);
    _mav_put_float(buf, 12, vibration_y);
    _mav_put_float(buf, 16, vibration_z);
    _mav_put_uint32_t(buf, 20, clipping_0);
    _mav_put_uint32_t(buf, 24, clipping_1);
    _mav_put_uint32_t(buf, 28, clipping_2);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VIBRATION_LEN);
#else
    mavlink_vibration_t packet;
    packet.time_usec = time_usec;
    packet.vibration_x = vibration_x;
    packet.vibration_y = vibration_y;
    packet.vibration_z = vibration_z;
    packet.clipping_0 = clipping_0;
    packet.clipping_1 = clipping_1;
    packet.clipping_2 = clipping_2;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VIBRATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_VIBRATION;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
}
 
/**
 * @brief Encode a vibration struct
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param vibration C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_vibration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vibration_t* vibration)
{
    return mavlink_msg_vibration_pack(system_id, component_id, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2);
}
 
/**
 * @brief Encode a vibration struct on a channel
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param vibration C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_vibration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vibration_t* vibration)
{
    return mavlink_msg_vibration_pack_chan(system_id, component_id, chan, msg, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2);
}
 
/**
 * @brief Send a vibration message
 * @param chan MAVLink channel to send the message
 *
 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
 * @param vibration_x  Vibration levels on X-axis
 * @param vibration_y  Vibration levels on Y-axis
 * @param vibration_z  Vibration levels on Z-axis
 * @param clipping_0  first accelerometer clipping count
 * @param clipping_1  second accelerometer clipping count
 * @param clipping_2  third accelerometer clipping count
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vibration_send(mavlink_channel_t chan, uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_VIBRATION_LEN];
    _mav_put_uint64_t(buf, 0, time_usec);
    _mav_put_float(buf, 8, vibration_x);
    _mav_put_float(buf, 12, vibration_y);
    _mav_put_float(buf, 16, vibration_z);
    _mav_put_uint32_t(buf, 20, clipping_0);
    _mav_put_uint32_t(buf, 24, clipping_1);
    _mav_put_uint32_t(buf, 28, clipping_2);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
#else
    mavlink_vibration_t packet;
    packet.time_usec = time_usec;
    packet.vibration_x = vibration_x;
    packet.vibration_y = vibration_y;
    packet.vibration_z = vibration_z;
    packet.clipping_0 = clipping_0;
    packet.clipping_1 = clipping_1;
    packet.clipping_2 = clipping_2;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)&packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
#endif
}
 
/**
 * @brief Send a vibration message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_vibration_send_struct(mavlink_channel_t chan, const mavlink_vibration_t* vibration)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_vibration_send(chan, vibration->time_usec, vibration->vibration_x, vibration->vibration_y, vibration->vibration_z, vibration->clipping_0, vibration->clipping_1, vibration->clipping_2);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)vibration, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_VIBRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This variant of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
static inline void mavlink_msg_vibration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, float vibration_x, float vibration_y, float vibration_z, uint32_t clipping_0, uint32_t clipping_1, uint32_t clipping_2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint64_t(buf, 0, time_usec);
    _mav_put_float(buf, 8, vibration_x);
    _mav_put_float(buf, 12, vibration_y);
    _mav_put_float(buf, 16, vibration_z);
    _mav_put_uint32_t(buf, 20, clipping_0);
    _mav_put_uint32_t(buf, 24, clipping_1);
    _mav_put_uint32_t(buf, 28, clipping_2);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, buf, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
#else
    mavlink_vibration_t *packet = (mavlink_vibration_t *)msgbuf;
    packet->time_usec = time_usec;
    packet->vibration_x = vibration_x;
    packet->vibration_y = vibration_y;
    packet->vibration_z = vibration_z;
    packet->clipping_0 = clipping_0;
    packet->clipping_1 = clipping_1;
    packet->clipping_2 = clipping_2;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VIBRATION, (const char *)packet, MAVLINK_MSG_ID_VIBRATION_MIN_LEN, MAVLINK_MSG_ID_VIBRATION_LEN, MAVLINK_MSG_ID_VIBRATION_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE VIBRATION UNPACKING
 
 
/**
 * @brief Get field time_usec from vibration message
 *
 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
 */
static inline uint64_t mavlink_msg_vibration_get_time_usec(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  0);
}
 
/**
 * @brief Get field vibration_x from vibration message
 *
 * @return  Vibration levels on X-axis
 */
static inline float mavlink_msg_vibration_get_vibration_x(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  8);
}
 
/**
 * @brief Get field vibration_y from vibration message
 *
 * @return  Vibration levels on Y-axis
 */
static inline float mavlink_msg_vibration_get_vibration_y(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  12);
}
 
/**
 * @brief Get field vibration_z from vibration message
 *
 * @return  Vibration levels on Z-axis
 */
static inline float mavlink_msg_vibration_get_vibration_z(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  16);
}
 
/**
 * @brief Get field clipping_0 from vibration message
 *
 * @return  first accelerometer clipping count
 */
static inline uint32_t mavlink_msg_vibration_get_clipping_0(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint32_t(msg,  20);
}
 
/**
 * @brief Get field clipping_1 from vibration message
 *
 * @return  second accelerometer clipping count
 */
static inline uint32_t mavlink_msg_vibration_get_clipping_1(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint32_t(msg,  24);
}
 
/**
 * @brief Get field clipping_2 from vibration message
 *
 * @return  third accelerometer clipping count
 */
static inline uint32_t mavlink_msg_vibration_get_clipping_2(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint32_t(msg,  28);
}
 
/**
 * @brief Decode a vibration message into a struct
 *
 * @param msg The message to decode
 * @param vibration C-struct to decode the message contents into
 */
static inline void mavlink_msg_vibration_decode(const mavlink_message_t* msg, mavlink_vibration_t* vibration)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    vibration->time_usec = mavlink_msg_vibration_get_time_usec(msg);
    vibration->vibration_x = mavlink_msg_vibration_get_vibration_x(msg);
    vibration->vibration_y = mavlink_msg_vibration_get_vibration_y(msg);
    vibration->vibration_z = mavlink_msg_vibration_get_vibration_z(msg);
    vibration->clipping_0 = mavlink_msg_vibration_get_clipping_0(msg);
    vibration->clipping_1 = mavlink_msg_vibration_get_clipping_1(msg);
    vibration->clipping_2 = mavlink_msg_vibration_get_clipping_2(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_VIBRATION_LEN? msg->len : MAVLINK_MSG_ID_VIBRATION_LEN;
        memset(vibration, 0, MAVLINK_MSG_ID_VIBRATION_LEN);
    memcpy(vibration, _MAV_PAYLOAD(msg), len);
#endif
}