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
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
#pragma once
// MESSAGE ASLCTRL_DATA PACKING
 
#define MAVLINK_MSG_ID_ASLCTRL_DATA 8004
 
 
typedef struct __mavlink_aslctrl_data_t {
 uint64_t timestamp; /*< [us]  Timestamp*/
 float h; /*<   See sourcecode for a description of these values... */
 float hRef; /*<   */
 float hRef_t; /*<   */
 float PitchAngle; /*< [deg] Pitch angle*/
 float PitchAngleRef; /*< [deg] Pitch angle reference*/
 float q; /*<   */
 float qRef; /*<   */
 float uElev; /*<   */
 float uThrot; /*<   */
 float uThrot2; /*<   */
 float nZ; /*<   */
 float AirspeedRef; /*< [m/s] Airspeed reference*/
 float YawAngle; /*< [deg] Yaw angle*/
 float YawAngleRef; /*< [deg] Yaw angle reference*/
 float RollAngle; /*< [deg] Roll angle*/
 float RollAngleRef; /*< [deg] Roll angle reference*/
 float p; /*<   */
 float pRef; /*<   */
 float r; /*<   */
 float rRef; /*<   */
 float uAil; /*<   */
 float uRud; /*<   */
 uint8_t aslctrl_mode; /*<   ASLCTRL control-mode (manual, stabilized, auto, etc...)*/
 uint8_t SpoilersEngaged; /*<   */
} mavlink_aslctrl_data_t;
 
#define MAVLINK_MSG_ID_ASLCTRL_DATA_LEN 98
#define MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN 98
#define MAVLINK_MSG_ID_8004_LEN 98
#define MAVLINK_MSG_ID_8004_MIN_LEN 98
 
#define MAVLINK_MSG_ID_ASLCTRL_DATA_CRC 172
#define MAVLINK_MSG_ID_8004_CRC 172
 
 
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ASLCTRL_DATA { \
    8004, \
    "ASLCTRL_DATA", \
    25, \
    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aslctrl_data_t, timestamp) }, \
         { "aslctrl_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_aslctrl_data_t, aslctrl_mode) }, \
         { "h", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aslctrl_data_t, h) }, \
         { "hRef", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aslctrl_data_t, hRef) }, \
         { "hRef_t", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aslctrl_data_t, hRef_t) }, \
         { "PitchAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aslctrl_data_t, PitchAngle) }, \
         { "PitchAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aslctrl_data_t, PitchAngleRef) }, \
         { "q", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aslctrl_data_t, q) }, \
         { "qRef", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aslctrl_data_t, qRef) }, \
         { "uElev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aslctrl_data_t, uElev) }, \
         { "uThrot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aslctrl_data_t, uThrot) }, \
         { "uThrot2", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aslctrl_data_t, uThrot2) }, \
         { "nZ", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aslctrl_data_t, nZ) }, \
         { "AirspeedRef", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aslctrl_data_t, AirspeedRef) }, \
         { "SpoilersEngaged", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_aslctrl_data_t, SpoilersEngaged) }, \
         { "YawAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aslctrl_data_t, YawAngle) }, \
         { "YawAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aslctrl_data_t, YawAngleRef) }, \
         { "RollAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aslctrl_data_t, RollAngle) }, \
         { "RollAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aslctrl_data_t, RollAngleRef) }, \
         { "p", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aslctrl_data_t, p) }, \
         { "pRef", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aslctrl_data_t, pRef) }, \
         { "r", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_aslctrl_data_t, r) }, \
         { "rRef", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_aslctrl_data_t, rRef) }, \
         { "uAil", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_aslctrl_data_t, uAil) }, \
         { "uRud", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_aslctrl_data_t, uRud) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_ASLCTRL_DATA { \
    "ASLCTRL_DATA", \
    25, \
    {  { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aslctrl_data_t, timestamp) }, \
         { "aslctrl_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 96, offsetof(mavlink_aslctrl_data_t, aslctrl_mode) }, \
         { "h", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aslctrl_data_t, h) }, \
         { "hRef", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aslctrl_data_t, hRef) }, \
         { "hRef_t", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aslctrl_data_t, hRef_t) }, \
         { "PitchAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aslctrl_data_t, PitchAngle) }, \
         { "PitchAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aslctrl_data_t, PitchAngleRef) }, \
         { "q", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aslctrl_data_t, q) }, \
         { "qRef", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aslctrl_data_t, qRef) }, \
         { "uElev", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aslctrl_data_t, uElev) }, \
         { "uThrot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aslctrl_data_t, uThrot) }, \
         { "uThrot2", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aslctrl_data_t, uThrot2) }, \
         { "nZ", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aslctrl_data_t, nZ) }, \
         { "AirspeedRef", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aslctrl_data_t, AirspeedRef) }, \
         { "SpoilersEngaged", NULL, MAVLINK_TYPE_UINT8_T, 0, 97, offsetof(mavlink_aslctrl_data_t, SpoilersEngaged) }, \
         { "YawAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aslctrl_data_t, YawAngle) }, \
         { "YawAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aslctrl_data_t, YawAngleRef) }, \
         { "RollAngle", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aslctrl_data_t, RollAngle) }, \
         { "RollAngleRef", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aslctrl_data_t, RollAngleRef) }, \
         { "p", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aslctrl_data_t, p) }, \
         { "pRef", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aslctrl_data_t, pRef) }, \
         { "r", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_aslctrl_data_t, r) }, \
         { "rRef", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_aslctrl_data_t, rRef) }, \
         { "uAil", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_aslctrl_data_t, uAil) }, \
         { "uRud", NULL, MAVLINK_TYPE_FLOAT, 0, 92, offsetof(mavlink_aslctrl_data_t, uRud) }, \
         } \
}
#endif
 
/**
 * @brief Pack a aslctrl_data 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 timestamp [us]  Timestamp
 * @param aslctrl_mode   ASLCTRL control-mode (manual, stabilized, auto, etc...)
 * @param h   See sourcecode for a description of these values... 
 * @param hRef   
 * @param hRef_t   
 * @param PitchAngle [deg] Pitch angle
 * @param PitchAngleRef [deg] Pitch angle reference
 * @param q   
 * @param qRef   
 * @param uElev   
 * @param uThrot   
 * @param uThrot2   
 * @param nZ   
 * @param AirspeedRef [m/s] Airspeed reference
 * @param SpoilersEngaged   
 * @param YawAngle [deg] Yaw angle
 * @param YawAngleRef [deg] Yaw angle reference
 * @param RollAngle [deg] Roll angle
 * @param RollAngleRef [deg] Roll angle reference
 * @param p   
 * @param pRef   
 * @param r   
 * @param rRef   
 * @param uAil   
 * @param uRud   
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_aslctrl_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint64_t timestamp, uint8_t aslctrl_mode, float h, float hRef, float hRef_t, float PitchAngle, float PitchAngleRef, float q, float qRef, float uElev, float uThrot, float uThrot2, float nZ, float AirspeedRef, uint8_t SpoilersEngaged, float YawAngle, float YawAngleRef, float RollAngle, float RollAngleRef, float p, float pRef, float r, float rRef, float uAil, float uRud)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ASLCTRL_DATA_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, h);
    _mav_put_float(buf, 12, hRef);
    _mav_put_float(buf, 16, hRef_t);
    _mav_put_float(buf, 20, PitchAngle);
    _mav_put_float(buf, 24, PitchAngleRef);
    _mav_put_float(buf, 28, q);
    _mav_put_float(buf, 32, qRef);
    _mav_put_float(buf, 36, uElev);
    _mav_put_float(buf, 40, uThrot);
    _mav_put_float(buf, 44, uThrot2);
    _mav_put_float(buf, 48, nZ);
    _mav_put_float(buf, 52, AirspeedRef);
    _mav_put_float(buf, 56, YawAngle);
    _mav_put_float(buf, 60, YawAngleRef);
    _mav_put_float(buf, 64, RollAngle);
    _mav_put_float(buf, 68, RollAngleRef);
    _mav_put_float(buf, 72, p);
    _mav_put_float(buf, 76, pRef);
    _mav_put_float(buf, 80, r);
    _mav_put_float(buf, 84, rRef);
    _mav_put_float(buf, 88, uAil);
    _mav_put_float(buf, 92, uRud);
    _mav_put_uint8_t(buf, 96, aslctrl_mode);
    _mav_put_uint8_t(buf, 97, SpoilersEngaged);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#else
    mavlink_aslctrl_data_t packet;
    packet.timestamp = timestamp;
    packet.h = h;
    packet.hRef = hRef;
    packet.hRef_t = hRef_t;
    packet.PitchAngle = PitchAngle;
    packet.PitchAngleRef = PitchAngleRef;
    packet.q = q;
    packet.qRef = qRef;
    packet.uElev = uElev;
    packet.uThrot = uThrot;
    packet.uThrot2 = uThrot2;
    packet.nZ = nZ;
    packet.AirspeedRef = AirspeedRef;
    packet.YawAngle = YawAngle;
    packet.YawAngleRef = YawAngleRef;
    packet.RollAngle = RollAngle;
    packet.RollAngleRef = RollAngleRef;
    packet.p = p;
    packet.pRef = pRef;
    packet.r = r;
    packet.rRef = rRef;
    packet.uAil = uAil;
    packet.uRud = uRud;
    packet.aslctrl_mode = aslctrl_mode;
    packet.SpoilersEngaged = SpoilersEngaged;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_ASLCTRL_DATA;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
}
 
/**
 * @brief Pack a aslctrl_data 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 timestamp [us]  Timestamp
 * @param aslctrl_mode   ASLCTRL control-mode (manual, stabilized, auto, etc...)
 * @param h   See sourcecode for a description of these values... 
 * @param hRef   
 * @param hRef_t   
 * @param PitchAngle [deg] Pitch angle
 * @param PitchAngleRef [deg] Pitch angle reference
 * @param q   
 * @param qRef   
 * @param uElev   
 * @param uThrot   
 * @param uThrot2   
 * @param nZ   
 * @param AirspeedRef [m/s] Airspeed reference
 * @param SpoilersEngaged   
 * @param YawAngle [deg] Yaw angle
 * @param YawAngleRef [deg] Yaw angle reference
 * @param RollAngle [deg] Roll angle
 * @param RollAngleRef [deg] Roll angle reference
 * @param p   
 * @param pRef   
 * @param r   
 * @param rRef   
 * @param uAil   
 * @param uRud   
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_aslctrl_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   uint64_t timestamp,uint8_t aslctrl_mode,float h,float hRef,float hRef_t,float PitchAngle,float PitchAngleRef,float q,float qRef,float uElev,float uThrot,float uThrot2,float nZ,float AirspeedRef,uint8_t SpoilersEngaged,float YawAngle,float YawAngleRef,float RollAngle,float RollAngleRef,float p,float pRef,float r,float rRef,float uAil,float uRud)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ASLCTRL_DATA_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, h);
    _mav_put_float(buf, 12, hRef);
    _mav_put_float(buf, 16, hRef_t);
    _mav_put_float(buf, 20, PitchAngle);
    _mav_put_float(buf, 24, PitchAngleRef);
    _mav_put_float(buf, 28, q);
    _mav_put_float(buf, 32, qRef);
    _mav_put_float(buf, 36, uElev);
    _mav_put_float(buf, 40, uThrot);
    _mav_put_float(buf, 44, uThrot2);
    _mav_put_float(buf, 48, nZ);
    _mav_put_float(buf, 52, AirspeedRef);
    _mav_put_float(buf, 56, YawAngle);
    _mav_put_float(buf, 60, YawAngleRef);
    _mav_put_float(buf, 64, RollAngle);
    _mav_put_float(buf, 68, RollAngleRef);
    _mav_put_float(buf, 72, p);
    _mav_put_float(buf, 76, pRef);
    _mav_put_float(buf, 80, r);
    _mav_put_float(buf, 84, rRef);
    _mav_put_float(buf, 88, uAil);
    _mav_put_float(buf, 92, uRud);
    _mav_put_uint8_t(buf, 96, aslctrl_mode);
    _mav_put_uint8_t(buf, 97, SpoilersEngaged);
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#else
    mavlink_aslctrl_data_t packet;
    packet.timestamp = timestamp;
    packet.h = h;
    packet.hRef = hRef;
    packet.hRef_t = hRef_t;
    packet.PitchAngle = PitchAngle;
    packet.PitchAngleRef = PitchAngleRef;
    packet.q = q;
    packet.qRef = qRef;
    packet.uElev = uElev;
    packet.uThrot = uThrot;
    packet.uThrot2 = uThrot2;
    packet.nZ = nZ;
    packet.AirspeedRef = AirspeedRef;
    packet.YawAngle = YawAngle;
    packet.YawAngleRef = YawAngleRef;
    packet.RollAngle = RollAngle;
    packet.RollAngleRef = RollAngleRef;
    packet.p = p;
    packet.pRef = pRef;
    packet.r = r;
    packet.rRef = rRef;
    packet.uAil = uAil;
    packet.uRud = uRud;
    packet.aslctrl_mode = aslctrl_mode;
    packet.SpoilersEngaged = SpoilersEngaged;
 
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_ASLCTRL_DATA;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
}
 
/**
 * @brief Encode a aslctrl_data 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 aslctrl_data C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_aslctrl_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aslctrl_data_t* aslctrl_data)
{
    return mavlink_msg_aslctrl_data_pack(system_id, component_id, msg, aslctrl_data->timestamp, aslctrl_data->aslctrl_mode, aslctrl_data->h, aslctrl_data->hRef, aslctrl_data->hRef_t, aslctrl_data->PitchAngle, aslctrl_data->PitchAngleRef, aslctrl_data->q, aslctrl_data->qRef, aslctrl_data->uElev, aslctrl_data->uThrot, aslctrl_data->uThrot2, aslctrl_data->nZ, aslctrl_data->AirspeedRef, aslctrl_data->SpoilersEngaged, aslctrl_data->YawAngle, aslctrl_data->YawAngleRef, aslctrl_data->RollAngle, aslctrl_data->RollAngleRef, aslctrl_data->p, aslctrl_data->pRef, aslctrl_data->r, aslctrl_data->rRef, aslctrl_data->uAil, aslctrl_data->uRud);
}
 
/**
 * @brief Encode a aslctrl_data 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 aslctrl_data C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_aslctrl_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aslctrl_data_t* aslctrl_data)
{
    return mavlink_msg_aslctrl_data_pack_chan(system_id, component_id, chan, msg, aslctrl_data->timestamp, aslctrl_data->aslctrl_mode, aslctrl_data->h, aslctrl_data->hRef, aslctrl_data->hRef_t, aslctrl_data->PitchAngle, aslctrl_data->PitchAngleRef, aslctrl_data->q, aslctrl_data->qRef, aslctrl_data->uElev, aslctrl_data->uThrot, aslctrl_data->uThrot2, aslctrl_data->nZ, aslctrl_data->AirspeedRef, aslctrl_data->SpoilersEngaged, aslctrl_data->YawAngle, aslctrl_data->YawAngleRef, aslctrl_data->RollAngle, aslctrl_data->RollAngleRef, aslctrl_data->p, aslctrl_data->pRef, aslctrl_data->r, aslctrl_data->rRef, aslctrl_data->uAil, aslctrl_data->uRud);
}
 
/**
 * @brief Send a aslctrl_data message
 * @param chan MAVLink channel to send the message
 *
 * @param timestamp [us]  Timestamp
 * @param aslctrl_mode   ASLCTRL control-mode (manual, stabilized, auto, etc...)
 * @param h   See sourcecode for a description of these values... 
 * @param hRef   
 * @param hRef_t   
 * @param PitchAngle [deg] Pitch angle
 * @param PitchAngleRef [deg] Pitch angle reference
 * @param q   
 * @param qRef   
 * @param uElev   
 * @param uThrot   
 * @param uThrot2   
 * @param nZ   
 * @param AirspeedRef [m/s] Airspeed reference
 * @param SpoilersEngaged   
 * @param YawAngle [deg] Yaw angle
 * @param YawAngleRef [deg] Yaw angle reference
 * @param RollAngle [deg] Roll angle
 * @param RollAngleRef [deg] Roll angle reference
 * @param p   
 * @param pRef   
 * @param r   
 * @param rRef   
 * @param uAil   
 * @param uRud   
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_aslctrl_data_send(mavlink_channel_t chan, uint64_t timestamp, uint8_t aslctrl_mode, float h, float hRef, float hRef_t, float PitchAngle, float PitchAngleRef, float q, float qRef, float uElev, float uThrot, float uThrot2, float nZ, float AirspeedRef, uint8_t SpoilersEngaged, float YawAngle, float YawAngleRef, float RollAngle, float RollAngleRef, float p, float pRef, float r, float rRef, float uAil, float uRud)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_ASLCTRL_DATA_LEN];
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, h);
    _mav_put_float(buf, 12, hRef);
    _mav_put_float(buf, 16, hRef_t);
    _mav_put_float(buf, 20, PitchAngle);
    _mav_put_float(buf, 24, PitchAngleRef);
    _mav_put_float(buf, 28, q);
    _mav_put_float(buf, 32, qRef);
    _mav_put_float(buf, 36, uElev);
    _mav_put_float(buf, 40, uThrot);
    _mav_put_float(buf, 44, uThrot2);
    _mav_put_float(buf, 48, nZ);
    _mav_put_float(buf, 52, AirspeedRef);
    _mav_put_float(buf, 56, YawAngle);
    _mav_put_float(buf, 60, YawAngleRef);
    _mav_put_float(buf, 64, RollAngle);
    _mav_put_float(buf, 68, RollAngleRef);
    _mav_put_float(buf, 72, p);
    _mav_put_float(buf, 76, pRef);
    _mav_put_float(buf, 80, r);
    _mav_put_float(buf, 84, rRef);
    _mav_put_float(buf, 88, uAil);
    _mav_put_float(buf, 92, uRud);
    _mav_put_uint8_t(buf, 96, aslctrl_mode);
    _mav_put_uint8_t(buf, 97, SpoilersEngaged);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASLCTRL_DATA, buf, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#else
    mavlink_aslctrl_data_t packet;
    packet.timestamp = timestamp;
    packet.h = h;
    packet.hRef = hRef;
    packet.hRef_t = hRef_t;
    packet.PitchAngle = PitchAngle;
    packet.PitchAngleRef = PitchAngleRef;
    packet.q = q;
    packet.qRef = qRef;
    packet.uElev = uElev;
    packet.uThrot = uThrot;
    packet.uThrot2 = uThrot2;
    packet.nZ = nZ;
    packet.AirspeedRef = AirspeedRef;
    packet.YawAngle = YawAngle;
    packet.YawAngleRef = YawAngleRef;
    packet.RollAngle = RollAngle;
    packet.RollAngleRef = RollAngleRef;
    packet.p = p;
    packet.pRef = pRef;
    packet.r = r;
    packet.rRef = rRef;
    packet.uAil = uAil;
    packet.uRud = uRud;
    packet.aslctrl_mode = aslctrl_mode;
    packet.SpoilersEngaged = SpoilersEngaged;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASLCTRL_DATA, (const char *)&packet, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#endif
}
 
/**
 * @brief Send a aslctrl_data message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_aslctrl_data_send_struct(mavlink_channel_t chan, const mavlink_aslctrl_data_t* aslctrl_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_aslctrl_data_send(chan, aslctrl_data->timestamp, aslctrl_data->aslctrl_mode, aslctrl_data->h, aslctrl_data->hRef, aslctrl_data->hRef_t, aslctrl_data->PitchAngle, aslctrl_data->PitchAngleRef, aslctrl_data->q, aslctrl_data->qRef, aslctrl_data->uElev, aslctrl_data->uThrot, aslctrl_data->uThrot2, aslctrl_data->nZ, aslctrl_data->AirspeedRef, aslctrl_data->SpoilersEngaged, aslctrl_data->YawAngle, aslctrl_data->YawAngleRef, aslctrl_data->RollAngle, aslctrl_data->RollAngleRef, aslctrl_data->p, aslctrl_data->pRef, aslctrl_data->r, aslctrl_data->rRef, aslctrl_data->uAil, aslctrl_data->uRud);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASLCTRL_DATA, (const char *)aslctrl_data, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_ASLCTRL_DATA_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_aslctrl_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t timestamp, uint8_t aslctrl_mode, float h, float hRef, float hRef_t, float PitchAngle, float PitchAngleRef, float q, float qRef, float uElev, float uThrot, float uThrot2, float nZ, float AirspeedRef, uint8_t SpoilersEngaged, float YawAngle, float YawAngleRef, float RollAngle, float RollAngleRef, float p, float pRef, float r, float rRef, float uAil, float uRud)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint64_t(buf, 0, timestamp);
    _mav_put_float(buf, 8, h);
    _mav_put_float(buf, 12, hRef);
    _mav_put_float(buf, 16, hRef_t);
    _mav_put_float(buf, 20, PitchAngle);
    _mav_put_float(buf, 24, PitchAngleRef);
    _mav_put_float(buf, 28, q);
    _mav_put_float(buf, 32, qRef);
    _mav_put_float(buf, 36, uElev);
    _mav_put_float(buf, 40, uThrot);
    _mav_put_float(buf, 44, uThrot2);
    _mav_put_float(buf, 48, nZ);
    _mav_put_float(buf, 52, AirspeedRef);
    _mav_put_float(buf, 56, YawAngle);
    _mav_put_float(buf, 60, YawAngleRef);
    _mav_put_float(buf, 64, RollAngle);
    _mav_put_float(buf, 68, RollAngleRef);
    _mav_put_float(buf, 72, p);
    _mav_put_float(buf, 76, pRef);
    _mav_put_float(buf, 80, r);
    _mav_put_float(buf, 84, rRef);
    _mav_put_float(buf, 88, uAil);
    _mav_put_float(buf, 92, uRud);
    _mav_put_uint8_t(buf, 96, aslctrl_mode);
    _mav_put_uint8_t(buf, 97, SpoilersEngaged);
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASLCTRL_DATA, buf, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#else
    mavlink_aslctrl_data_t *packet = (mavlink_aslctrl_data_t *)msgbuf;
    packet->timestamp = timestamp;
    packet->h = h;
    packet->hRef = hRef;
    packet->hRef_t = hRef_t;
    packet->PitchAngle = PitchAngle;
    packet->PitchAngleRef = PitchAngleRef;
    packet->q = q;
    packet->qRef = qRef;
    packet->uElev = uElev;
    packet->uThrot = uThrot;
    packet->uThrot2 = uThrot2;
    packet->nZ = nZ;
    packet->AirspeedRef = AirspeedRef;
    packet->YawAngle = YawAngle;
    packet->YawAngleRef = YawAngleRef;
    packet->RollAngle = RollAngle;
    packet->RollAngleRef = RollAngleRef;
    packet->p = p;
    packet->pRef = pRef;
    packet->r = r;
    packet->rRef = rRef;
    packet->uAil = uAil;
    packet->uRud = uRud;
    packet->aslctrl_mode = aslctrl_mode;
    packet->SpoilersEngaged = SpoilersEngaged;
 
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ASLCTRL_DATA, (const char *)packet, MAVLINK_MSG_ID_ASLCTRL_DATA_MIN_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN, MAVLINK_MSG_ID_ASLCTRL_DATA_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE ASLCTRL_DATA UNPACKING
 
 
/**
 * @brief Get field timestamp from aslctrl_data message
 *
 * @return [us]  Timestamp
 */
static inline uint64_t mavlink_msg_aslctrl_data_get_timestamp(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint64_t(msg,  0);
}
 
/**
 * @brief Get field aslctrl_mode from aslctrl_data message
 *
 * @return   ASLCTRL control-mode (manual, stabilized, auto, etc...)
 */
static inline uint8_t mavlink_msg_aslctrl_data_get_aslctrl_mode(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  96);
}
 
/**
 * @brief Get field h from aslctrl_data message
 *
 * @return   See sourcecode for a description of these values... 
 */
static inline float mavlink_msg_aslctrl_data_get_h(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  8);
}
 
/**
 * @brief Get field hRef from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_hRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  12);
}
 
/**
 * @brief Get field hRef_t from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_hRef_t(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  16);
}
 
/**
 * @brief Get field PitchAngle from aslctrl_data message
 *
 * @return [deg] Pitch angle
 */
static inline float mavlink_msg_aslctrl_data_get_PitchAngle(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  20);
}
 
/**
 * @brief Get field PitchAngleRef from aslctrl_data message
 *
 * @return [deg] Pitch angle reference
 */
static inline float mavlink_msg_aslctrl_data_get_PitchAngleRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  24);
}
 
/**
 * @brief Get field q from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_q(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  28);
}
 
/**
 * @brief Get field qRef from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_qRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  32);
}
 
/**
 * @brief Get field uElev from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_uElev(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  36);
}
 
/**
 * @brief Get field uThrot from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_uThrot(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  40);
}
 
/**
 * @brief Get field uThrot2 from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_uThrot2(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  44);
}
 
/**
 * @brief Get field nZ from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_nZ(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  48);
}
 
/**
 * @brief Get field AirspeedRef from aslctrl_data message
 *
 * @return [m/s] Airspeed reference
 */
static inline float mavlink_msg_aslctrl_data_get_AirspeedRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  52);
}
 
/**
 * @brief Get field SpoilersEngaged from aslctrl_data message
 *
 * @return   
 */
static inline uint8_t mavlink_msg_aslctrl_data_get_SpoilersEngaged(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  97);
}
 
/**
 * @brief Get field YawAngle from aslctrl_data message
 *
 * @return [deg] Yaw angle
 */
static inline float mavlink_msg_aslctrl_data_get_YawAngle(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  56);
}
 
/**
 * @brief Get field YawAngleRef from aslctrl_data message
 *
 * @return [deg] Yaw angle reference
 */
static inline float mavlink_msg_aslctrl_data_get_YawAngleRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  60);
}
 
/**
 * @brief Get field RollAngle from aslctrl_data message
 *
 * @return [deg] Roll angle
 */
static inline float mavlink_msg_aslctrl_data_get_RollAngle(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  64);
}
 
/**
 * @brief Get field RollAngleRef from aslctrl_data message
 *
 * @return [deg] Roll angle reference
 */
static inline float mavlink_msg_aslctrl_data_get_RollAngleRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  68);
}
 
/**
 * @brief Get field p from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_p(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  72);
}
 
/**
 * @brief Get field pRef from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_pRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  76);
}
 
/**
 * @brief Get field r from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_r(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  80);
}
 
/**
 * @brief Get field rRef from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_rRef(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  84);
}
 
/**
 * @brief Get field uAil from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_uAil(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  88);
}
 
/**
 * @brief Get field uRud from aslctrl_data message
 *
 * @return   
 */
static inline float mavlink_msg_aslctrl_data_get_uRud(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  92);
}
 
/**
 * @brief Decode a aslctrl_data message into a struct
 *
 * @param msg The message to decode
 * @param aslctrl_data C-struct to decode the message contents into
 */
static inline void mavlink_msg_aslctrl_data_decode(const mavlink_message_t* msg, mavlink_aslctrl_data_t* aslctrl_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    aslctrl_data->timestamp = mavlink_msg_aslctrl_data_get_timestamp(msg);
    aslctrl_data->h = mavlink_msg_aslctrl_data_get_h(msg);
    aslctrl_data->hRef = mavlink_msg_aslctrl_data_get_hRef(msg);
    aslctrl_data->hRef_t = mavlink_msg_aslctrl_data_get_hRef_t(msg);
    aslctrl_data->PitchAngle = mavlink_msg_aslctrl_data_get_PitchAngle(msg);
    aslctrl_data->PitchAngleRef = mavlink_msg_aslctrl_data_get_PitchAngleRef(msg);
    aslctrl_data->q = mavlink_msg_aslctrl_data_get_q(msg);
    aslctrl_data->qRef = mavlink_msg_aslctrl_data_get_qRef(msg);
    aslctrl_data->uElev = mavlink_msg_aslctrl_data_get_uElev(msg);
    aslctrl_data->uThrot = mavlink_msg_aslctrl_data_get_uThrot(msg);
    aslctrl_data->uThrot2 = mavlink_msg_aslctrl_data_get_uThrot2(msg);
    aslctrl_data->nZ = mavlink_msg_aslctrl_data_get_nZ(msg);
    aslctrl_data->AirspeedRef = mavlink_msg_aslctrl_data_get_AirspeedRef(msg);
    aslctrl_data->YawAngle = mavlink_msg_aslctrl_data_get_YawAngle(msg);
    aslctrl_data->YawAngleRef = mavlink_msg_aslctrl_data_get_YawAngleRef(msg);
    aslctrl_data->RollAngle = mavlink_msg_aslctrl_data_get_RollAngle(msg);
    aslctrl_data->RollAngleRef = mavlink_msg_aslctrl_data_get_RollAngleRef(msg);
    aslctrl_data->p = mavlink_msg_aslctrl_data_get_p(msg);
    aslctrl_data->pRef = mavlink_msg_aslctrl_data_get_pRef(msg);
    aslctrl_data->r = mavlink_msg_aslctrl_data_get_r(msg);
    aslctrl_data->rRef = mavlink_msg_aslctrl_data_get_rRef(msg);
    aslctrl_data->uAil = mavlink_msg_aslctrl_data_get_uAil(msg);
    aslctrl_data->uRud = mavlink_msg_aslctrl_data_get_uRud(msg);
    aslctrl_data->aslctrl_mode = mavlink_msg_aslctrl_data_get_aslctrl_mode(msg);
    aslctrl_data->SpoilersEngaged = mavlink_msg_aslctrl_data_get_SpoilersEngaged(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_ASLCTRL_DATA_LEN? msg->len : MAVLINK_MSG_ID_ASLCTRL_DATA_LEN;
        memset(aslctrl_data, 0, MAVLINK_MSG_ID_ASLCTRL_DATA_LEN);
    memcpy(aslctrl_data, _MAV_PAYLOAD(msg), len);
#endif
}