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
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
#pragma once
// MESSAGE ICAROUS_KINEMATIC_BANDS PACKING
 
#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS 42001
 
 
typedef struct __mavlink_icarous_kinematic_bands_t {
 float min1; /*< [deg] min angle (degrees)*/
 float max1; /*< [deg] max angle (degrees)*/
 float min2; /*< [deg] min angle (degrees)*/
 float max2; /*< [deg] max angle (degrees)*/
 float min3; /*< [deg] min angle (degrees)*/
 float max3; /*< [deg] max angle (degrees)*/
 float min4; /*< [deg] min angle (degrees)*/
 float max4; /*< [deg] max angle (degrees)*/
 float min5; /*< [deg] min angle (degrees)*/
 float max5; /*< [deg] max angle (degrees)*/
 int8_t numBands; /*<  Number of track bands*/
 uint8_t type1; /*<  See the TRACK_BAND_TYPES enum.*/
 uint8_t type2; /*<  See the TRACK_BAND_TYPES enum.*/
 uint8_t type3; /*<  See the TRACK_BAND_TYPES enum.*/
 uint8_t type4; /*<  See the TRACK_BAND_TYPES enum.*/
 uint8_t type5; /*<  See the TRACK_BAND_TYPES enum.*/
} mavlink_icarous_kinematic_bands_t;
 
#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN 46
#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN 46
#define MAVLINK_MSG_ID_42001_LEN 46
#define MAVLINK_MSG_ID_42001_MIN_LEN 46
 
#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC 239
#define MAVLINK_MSG_ID_42001_CRC 239
 
 
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS { \
    42001, \
    "ICAROUS_KINEMATIC_BANDS", \
    16, \
    {  { "numBands", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_icarous_kinematic_bands_t, numBands) }, \
         { "type1", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_icarous_kinematic_bands_t, type1) }, \
         { "min1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_icarous_kinematic_bands_t, min1) }, \
         { "max1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_icarous_kinematic_bands_t, max1) }, \
         { "type2", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_icarous_kinematic_bands_t, type2) }, \
         { "min2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_icarous_kinematic_bands_t, min2) }, \
         { "max2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_icarous_kinematic_bands_t, max2) }, \
         { "type3", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_icarous_kinematic_bands_t, type3) }, \
         { "min3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_icarous_kinematic_bands_t, min3) }, \
         { "max3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_icarous_kinematic_bands_t, max3) }, \
         { "type4", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_icarous_kinematic_bands_t, type4) }, \
         { "min4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_icarous_kinematic_bands_t, min4) }, \
         { "max4", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_icarous_kinematic_bands_t, max4) }, \
         { "type5", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_icarous_kinematic_bands_t, type5) }, \
         { "min5", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_icarous_kinematic_bands_t, min5) }, \
         { "max5", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_icarous_kinematic_bands_t, max5) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS { \
    "ICAROUS_KINEMATIC_BANDS", \
    16, \
    {  { "numBands", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_icarous_kinematic_bands_t, numBands) }, \
         { "type1", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_icarous_kinematic_bands_t, type1) }, \
         { "min1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_icarous_kinematic_bands_t, min1) }, \
         { "max1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_icarous_kinematic_bands_t, max1) }, \
         { "type2", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_icarous_kinematic_bands_t, type2) }, \
         { "min2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_icarous_kinematic_bands_t, min2) }, \
         { "max2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_icarous_kinematic_bands_t, max2) }, \
         { "type3", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_icarous_kinematic_bands_t, type3) }, \
         { "min3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_icarous_kinematic_bands_t, min3) }, \
         { "max3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_icarous_kinematic_bands_t, max3) }, \
         { "type4", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_icarous_kinematic_bands_t, type4) }, \
         { "min4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_icarous_kinematic_bands_t, min4) }, \
         { "max4", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_icarous_kinematic_bands_t, max4) }, \
         { "type5", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_icarous_kinematic_bands_t, type5) }, \
         { "min5", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_icarous_kinematic_bands_t, min5) }, \
         { "max5", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_icarous_kinematic_bands_t, max5) }, \
         } \
}
#endif
 
/**
 * @brief Pack a icarous_kinematic_bands 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 numBands  Number of track bands
 * @param type1  See the TRACK_BAND_TYPES enum.
 * @param min1 [deg] min angle (degrees)
 * @param max1 [deg] max angle (degrees)
 * @param type2  See the TRACK_BAND_TYPES enum.
 * @param min2 [deg] min angle (degrees)
 * @param max2 [deg] max angle (degrees)
 * @param type3  See the TRACK_BAND_TYPES enum.
 * @param min3 [deg] min angle (degrees)
 * @param max3 [deg] max angle (degrees)
 * @param type4  See the TRACK_BAND_TYPES enum.
 * @param min4 [deg] min angle (degrees)
 * @param max4 [deg] max angle (degrees)
 * @param type5  See the TRACK_BAND_TYPES enum.
 * @param min5 [deg] min angle (degrees)
 * @param max5 [deg] max angle (degrees)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_icarous_kinematic_bands_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
    _mav_put_float(buf, 0, min1);
    _mav_put_float(buf, 4, max1);
    _mav_put_float(buf, 8, min2);
    _mav_put_float(buf, 12, max2);
    _mav_put_float(buf, 16, min3);
    _mav_put_float(buf, 20, max3);
    _mav_put_float(buf, 24, min4);
    _mav_put_float(buf, 28, max4);
    _mav_put_float(buf, 32, min5);
    _mav_put_float(buf, 36, max5);
    _mav_put_int8_t(buf, 40, numBands);
    _mav_put_uint8_t(buf, 41, type1);
    _mav_put_uint8_t(buf, 42, type2);
    _mav_put_uint8_t(buf, 43, type3);
    _mav_put_uint8_t(buf, 44, type4);
    _mav_put_uint8_t(buf, 45, type5);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
#else
    mavlink_icarous_kinematic_bands_t packet;
    packet.min1 = min1;
    packet.max1 = max1;
    packet.min2 = min2;
    packet.max2 = max2;
    packet.min3 = min3;
    packet.max3 = max3;
    packet.min4 = min4;
    packet.max4 = max4;
    packet.min5 = min5;
    packet.max5 = max5;
    packet.numBands = numBands;
    packet.type1 = type1;
    packet.type2 = type2;
    packet.type3 = type3;
    packet.type4 = type4;
    packet.type5 = type5;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
}
 
/**
 * @brief Pack a icarous_kinematic_bands 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 numBands  Number of track bands
 * @param type1  See the TRACK_BAND_TYPES enum.
 * @param min1 [deg] min angle (degrees)
 * @param max1 [deg] max angle (degrees)
 * @param type2  See the TRACK_BAND_TYPES enum.
 * @param min2 [deg] min angle (degrees)
 * @param max2 [deg] max angle (degrees)
 * @param type3  See the TRACK_BAND_TYPES enum.
 * @param min3 [deg] min angle (degrees)
 * @param max3 [deg] max angle (degrees)
 * @param type4  See the TRACK_BAND_TYPES enum.
 * @param min4 [deg] min angle (degrees)
 * @param max4 [deg] max angle (degrees)
 * @param type5  See the TRACK_BAND_TYPES enum.
 * @param min5 [deg] min angle (degrees)
 * @param max5 [deg] max angle (degrees)
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_icarous_kinematic_bands_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   int8_t numBands,uint8_t type1,float min1,float max1,uint8_t type2,float min2,float max2,uint8_t type3,float min3,float max3,uint8_t type4,float min4,float max4,uint8_t type5,float min5,float max5)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
    _mav_put_float(buf, 0, min1);
    _mav_put_float(buf, 4, max1);
    _mav_put_float(buf, 8, min2);
    _mav_put_float(buf, 12, max2);
    _mav_put_float(buf, 16, min3);
    _mav_put_float(buf, 20, max3);
    _mav_put_float(buf, 24, min4);
    _mav_put_float(buf, 28, max4);
    _mav_put_float(buf, 32, min5);
    _mav_put_float(buf, 36, max5);
    _mav_put_int8_t(buf, 40, numBands);
    _mav_put_uint8_t(buf, 41, type1);
    _mav_put_uint8_t(buf, 42, type2);
    _mav_put_uint8_t(buf, 43, type3);
    _mav_put_uint8_t(buf, 44, type4);
    _mav_put_uint8_t(buf, 45, type5);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
#else
    mavlink_icarous_kinematic_bands_t packet;
    packet.min1 = min1;
    packet.max1 = max1;
    packet.min2 = min2;
    packet.max2 = max2;
    packet.min3 = min3;
    packet.max3 = max3;
    packet.min4 = min4;
    packet.max4 = max4;
    packet.min5 = min5;
    packet.max5 = max5;
    packet.numBands = numBands;
    packet.type1 = type1;
    packet.type2 = type2;
    packet.type3 = type3;
    packet.type4 = type4;
    packet.type5 = type5;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
}
 
/**
 * @brief Encode a icarous_kinematic_bands 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 icarous_kinematic_bands C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_icarous_kinematic_bands_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
{
    return mavlink_msg_icarous_kinematic_bands_pack(system_id, component_id, msg, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
}
 
/**
 * @brief Encode a icarous_kinematic_bands 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 icarous_kinematic_bands C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_icarous_kinematic_bands_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
{
    return mavlink_msg_icarous_kinematic_bands_pack_chan(system_id, component_id, chan, msg, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
}
 
/**
 * @brief Send a icarous_kinematic_bands message
 * @param chan MAVLink channel to send the message
 *
 * @param numBands  Number of track bands
 * @param type1  See the TRACK_BAND_TYPES enum.
 * @param min1 [deg] min angle (degrees)
 * @param max1 [deg] max angle (degrees)
 * @param type2  See the TRACK_BAND_TYPES enum.
 * @param min2 [deg] min angle (degrees)
 * @param max2 [deg] max angle (degrees)
 * @param type3  See the TRACK_BAND_TYPES enum.
 * @param min3 [deg] min angle (degrees)
 * @param max3 [deg] max angle (degrees)
 * @param type4  See the TRACK_BAND_TYPES enum.
 * @param min4 [deg] min angle (degrees)
 * @param max4 [deg] max angle (degrees)
 * @param type5  See the TRACK_BAND_TYPES enum.
 * @param min5 [deg] min angle (degrees)
 * @param max5 [deg] max angle (degrees)
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_icarous_kinematic_bands_send(mavlink_channel_t chan, int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
    _mav_put_float(buf, 0, min1);
    _mav_put_float(buf, 4, max1);
    _mav_put_float(buf, 8, min2);
    _mav_put_float(buf, 12, max2);
    _mav_put_float(buf, 16, min3);
    _mav_put_float(buf, 20, max3);
    _mav_put_float(buf, 24, min4);
    _mav_put_float(buf, 28, max4);
    _mav_put_float(buf, 32, min5);
    _mav_put_float(buf, 36, max5);
    _mav_put_int8_t(buf, 40, numBands);
    _mav_put_uint8_t(buf, 41, type1);
    _mav_put_uint8_t(buf, 42, type2);
    _mav_put_uint8_t(buf, 43, type3);
    _mav_put_uint8_t(buf, 44, type4);
    _mav_put_uint8_t(buf, 45, type5);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
#else
    mavlink_icarous_kinematic_bands_t packet;
    packet.min1 = min1;
    packet.max1 = max1;
    packet.min2 = min2;
    packet.max2 = max2;
    packet.min3 = min3;
    packet.max3 = max3;
    packet.min4 = min4;
    packet.max4 = max4;
    packet.min5 = min5;
    packet.max5 = max5;
    packet.numBands = numBands;
    packet.type1 = type1;
    packet.type2 = type2;
    packet.type3 = type3;
    packet.type4 = type4;
    packet.type5 = type5;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)&packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
#endif
}
 
/**
 * @brief Send a icarous_kinematic_bands message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_icarous_kinematic_bands_send_struct(mavlink_channel_t chan, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_icarous_kinematic_bands_send(chan, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)icarous_kinematic_bands, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_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_icarous_kinematic_bands_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_float(buf, 0, min1);
    _mav_put_float(buf, 4, max1);
    _mav_put_float(buf, 8, min2);
    _mav_put_float(buf, 12, max2);
    _mav_put_float(buf, 16, min3);
    _mav_put_float(buf, 20, max3);
    _mav_put_float(buf, 24, min4);
    _mav_put_float(buf, 28, max4);
    _mav_put_float(buf, 32, min5);
    _mav_put_float(buf, 36, max5);
    _mav_put_int8_t(buf, 40, numBands);
    _mav_put_uint8_t(buf, 41, type1);
    _mav_put_uint8_t(buf, 42, type2);
    _mav_put_uint8_t(buf, 43, type3);
    _mav_put_uint8_t(buf, 44, type4);
    _mav_put_uint8_t(buf, 45, type5);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
#else
    mavlink_icarous_kinematic_bands_t *packet = (mavlink_icarous_kinematic_bands_t *)msgbuf;
    packet->min1 = min1;
    packet->max1 = max1;
    packet->min2 = min2;
    packet->max2 = max2;
    packet->min3 = min3;
    packet->max3 = max3;
    packet->min4 = min4;
    packet->max4 = max4;
    packet->min5 = min5;
    packet->max5 = max5;
    packet->numBands = numBands;
    packet->type1 = type1;
    packet->type2 = type2;
    packet->type3 = type3;
    packet->type4 = type4;
    packet->type5 = type5;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE ICAROUS_KINEMATIC_BANDS UNPACKING
 
 
/**
 * @brief Get field numBands from icarous_kinematic_bands message
 *
 * @return  Number of track bands
 */
static inline int8_t mavlink_msg_icarous_kinematic_bands_get_numBands(const mavlink_message_t* msg)
{
    return _MAV_RETURN_int8_t(msg,  40);
}
 
/**
 * @brief Get field type1 from icarous_kinematic_bands message
 *
 * @return  See the TRACK_BAND_TYPES enum.
 */
static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type1(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  41);
}
 
/**
 * @brief Get field min1 from icarous_kinematic_bands message
 *
 * @return [deg] min angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_min1(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  0);
}
 
/**
 * @brief Get field max1 from icarous_kinematic_bands message
 *
 * @return [deg] max angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_max1(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  4);
}
 
/**
 * @brief Get field type2 from icarous_kinematic_bands message
 *
 * @return  See the TRACK_BAND_TYPES enum.
 */
static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type2(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  42);
}
 
/**
 * @brief Get field min2 from icarous_kinematic_bands message
 *
 * @return [deg] min angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_min2(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  8);
}
 
/**
 * @brief Get field max2 from icarous_kinematic_bands message
 *
 * @return [deg] max angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_max2(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  12);
}
 
/**
 * @brief Get field type3 from icarous_kinematic_bands message
 *
 * @return  See the TRACK_BAND_TYPES enum.
 */
static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type3(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  43);
}
 
/**
 * @brief Get field min3 from icarous_kinematic_bands message
 *
 * @return [deg] min angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_min3(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  16);
}
 
/**
 * @brief Get field max3 from icarous_kinematic_bands message
 *
 * @return [deg] max angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_max3(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  20);
}
 
/**
 * @brief Get field type4 from icarous_kinematic_bands message
 *
 * @return  See the TRACK_BAND_TYPES enum.
 */
static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type4(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  44);
}
 
/**
 * @brief Get field min4 from icarous_kinematic_bands message
 *
 * @return [deg] min angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_min4(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  24);
}
 
/**
 * @brief Get field max4 from icarous_kinematic_bands message
 *
 * @return [deg] max angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_max4(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  28);
}
 
/**
 * @brief Get field type5 from icarous_kinematic_bands message
 *
 * @return  See the TRACK_BAND_TYPES enum.
 */
static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type5(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  45);
}
 
/**
 * @brief Get field min5 from icarous_kinematic_bands message
 *
 * @return [deg] min angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_min5(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  32);
}
 
/**
 * @brief Get field max5 from icarous_kinematic_bands message
 *
 * @return [deg] max angle (degrees)
 */
static inline float mavlink_msg_icarous_kinematic_bands_get_max5(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  36);
}
 
/**
 * @brief Decode a icarous_kinematic_bands message into a struct
 *
 * @param msg The message to decode
 * @param icarous_kinematic_bands C-struct to decode the message contents into
 */
static inline void mavlink_msg_icarous_kinematic_bands_decode(const mavlink_message_t* msg, mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    icarous_kinematic_bands->min1 = mavlink_msg_icarous_kinematic_bands_get_min1(msg);
    icarous_kinematic_bands->max1 = mavlink_msg_icarous_kinematic_bands_get_max1(msg);
    icarous_kinematic_bands->min2 = mavlink_msg_icarous_kinematic_bands_get_min2(msg);
    icarous_kinematic_bands->max2 = mavlink_msg_icarous_kinematic_bands_get_max2(msg);
    icarous_kinematic_bands->min3 = mavlink_msg_icarous_kinematic_bands_get_min3(msg);
    icarous_kinematic_bands->max3 = mavlink_msg_icarous_kinematic_bands_get_max3(msg);
    icarous_kinematic_bands->min4 = mavlink_msg_icarous_kinematic_bands_get_min4(msg);
    icarous_kinematic_bands->max4 = mavlink_msg_icarous_kinematic_bands_get_max4(msg);
    icarous_kinematic_bands->min5 = mavlink_msg_icarous_kinematic_bands_get_min5(msg);
    icarous_kinematic_bands->max5 = mavlink_msg_icarous_kinematic_bands_get_max5(msg);
    icarous_kinematic_bands->numBands = mavlink_msg_icarous_kinematic_bands_get_numBands(msg);
    icarous_kinematic_bands->type1 = mavlink_msg_icarous_kinematic_bands_get_type1(msg);
    icarous_kinematic_bands->type2 = mavlink_msg_icarous_kinematic_bands_get_type2(msg);
    icarous_kinematic_bands->type3 = mavlink_msg_icarous_kinematic_bands_get_type3(msg);
    icarous_kinematic_bands->type4 = mavlink_msg_icarous_kinematic_bands_get_type4(msg);
    icarous_kinematic_bands->type5 = mavlink_msg_icarous_kinematic_bands_get_type5(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN? msg->len : MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN;
        memset(icarous_kinematic_bands, 0, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
    memcpy(icarous_kinematic_bands, _MAV_PAYLOAD(msg), len);
#endif
}