-
Notifications
You must be signed in to change notification settings - Fork 7
/
Copy pathMavLink.generated.cs
10507 lines (8306 loc) · 271 KB
/
MavLink.generated.cs
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
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
MAVLink protocol implementation (auto-generated by mavgen.py)
Generated from: common.xml
Note: this file has been auto-generated. DO NOT EDIT
*/
using System;
using System.Reflection;
namespace MavLink
{
/// <summary>
/// Micro air vehicle / autopilot classes. This identifies the individual model.
/// </summary>
public enum MAV_AUTOPILOT : uint
{
/// <summary>
/// Generic autopilot, full support for everything
/// </summary>
MAV_AUTOPILOT_GENERIC = 0,
/// <summary>
/// Reserved for future use.
/// </summary>
MAV_AUTOPILOT_RESERVED = 1,
/// <summary>
/// SLUGS autopilot, http://slugsuav.soe.ucsc.edu
/// </summary>
MAV_AUTOPILOT_SLUGS = 2,
/// <summary>
/// ArduPilotMega / ArduCopter, http://diydrones.com
/// </summary>
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
/// <summary>
/// OpenPilot, http://openpilot.org
/// </summary>
MAV_AUTOPILOT_OPENPILOT = 4,
/// <summary>
/// Generic autopilot only supporting simple waypoints
/// </summary>
MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
/// <summary>
/// Generic autopilot supporting waypoints and other simple navigation commands
/// </summary>
MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
/// <summary>
/// Generic autopilot supporting the full mission command set
/// </summary>
MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
/// <summary>
/// No valid autopilot, e.g. a GCS or other MAVLink component
/// </summary>
MAV_AUTOPILOT_INVALID = 8,
/// <summary>
/// PPZ UAV - http://nongnu.org/paparazzi
/// </summary>
MAV_AUTOPILOT_PPZ = 9,
/// <summary>
/// UAV Dev Board
/// </summary>
MAV_AUTOPILOT_UDB = 10,
/// <summary>
/// FlexiPilot
/// </summary>
MAV_AUTOPILOT_FP = 11,
/// <summary>
/// PX4 Autopilot - http://pixhawk.ethz.ch/px4/
/// </summary>
MAV_AUTOPILOT_PX4 = 12,
/// <summary>
/// SMACCMPilot - http://smaccmpilot.org
/// </summary>
MAV_AUTOPILOT_SMACCMPILOT = 13,
/// <summary>
/// AutoQuad -- http://autoquad.org
/// </summary>
MAV_AUTOPILOT_AUTOQUAD = 14,
/// <summary>
/// Armazila -- http://armazila.com
/// </summary>
MAV_AUTOPILOT_ARMAZILA = 15,
/// <summary>
/// Aerob -- http://aerob.ru
/// </summary>
MAV_AUTOPILOT_AEROB = 16,
/// <summary>
/// ASLUAV autopilot -- http://www.asl.ethz.ch
/// </summary>
MAV_AUTOPILOT_ASLUAV = 17,
/// <summary>
/// SmartAP Autopilot - http://sky-drones.com
/// </summary>
MAV_AUTOPILOT_SMARTAP = 18,
/// <summary>
/// AirRails - http://uaventure.com
/// </summary>
MAV_AUTOPILOT_AIRRAILS = 19,
MAV_AUTOPILOT_ENUM_END = 20,
}
/// <summary>
///
/// </summary>
public enum MAV_TYPE : uint
{
/// <summary>
/// Generic micro air vehicle.
/// </summary>
MAV_TYPE_GENERIC = 0,
/// <summary>
/// Fixed wing aircraft.
/// </summary>
MAV_TYPE_FIXED_WING = 1,
/// <summary>
/// Quadrotor
/// </summary>
MAV_TYPE_QUADROTOR = 2,
/// <summary>
/// Coaxial helicopter
/// </summary>
MAV_TYPE_COAXIAL = 3,
/// <summary>
/// Normal helicopter with tail rotor.
/// </summary>
MAV_TYPE_HELICOPTER = 4,
/// <summary>
/// Ground installation
/// </summary>
MAV_TYPE_ANTENNA_TRACKER = 5,
/// <summary>
/// Operator control unit / ground control station
/// </summary>
MAV_TYPE_GCS = 6,
/// <summary>
/// Airship, controlled
/// </summary>
MAV_TYPE_AIRSHIP = 7,
/// <summary>
/// Free balloon, uncontrolled
/// </summary>
MAV_TYPE_FREE_BALLOON = 8,
/// <summary>
/// Rocket
/// </summary>
MAV_TYPE_ROCKET = 9,
/// <summary>
/// Ground rover
/// </summary>
MAV_TYPE_GROUND_ROVER = 10,
/// <summary>
/// Surface vessel, boat, ship
/// </summary>
MAV_TYPE_SURFACE_BOAT = 11,
/// <summary>
/// Submarine
/// </summary>
MAV_TYPE_SUBMARINE = 12,
/// <summary>
/// Hexarotor
/// </summary>
MAV_TYPE_HEXAROTOR = 13,
/// <summary>
/// Octorotor
/// </summary>
MAV_TYPE_OCTOROTOR = 14,
/// <summary>
/// Tricopter
/// </summary>
MAV_TYPE_TRICOPTER = 15,
/// <summary>
/// Flapping wing
/// </summary>
MAV_TYPE_FLAPPING_WING = 16,
/// <summary>
/// Kite
/// </summary>
MAV_TYPE_KITE = 17,
/// <summary>
/// Onboard companion controller
/// </summary>
MAV_TYPE_ONBOARD_CONTROLLER = 18,
/// <summary>
/// Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
/// </summary>
MAV_TYPE_VTOL_DUOROTOR = 19,
/// <summary>
/// Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
/// </summary>
MAV_TYPE_VTOL_QUADROTOR = 20,
/// <summary>
/// Tiltrotor VTOL
/// </summary>
MAV_TYPE_VTOL_TILTROTOR = 21,
/// <summary>
/// VTOL reserved 2
/// </summary>
MAV_TYPE_VTOL_RESERVED2 = 22,
/// <summary>
/// VTOL reserved 3
/// </summary>
MAV_TYPE_VTOL_RESERVED3 = 23,
/// <summary>
/// VTOL reserved 4
/// </summary>
MAV_TYPE_VTOL_RESERVED4 = 24,
/// <summary>
/// VTOL reserved 5
/// </summary>
MAV_TYPE_VTOL_RESERVED5 = 25,
/// <summary>
/// Onboard gimbal
/// </summary>
MAV_TYPE_GIMBAL = 26,
/// <summary>
/// Onboard ADSB peripheral
/// </summary>
MAV_TYPE_ADSB = 27,
/// <summary>
/// Steerable, nonrigid airfoil
/// </summary>
MAV_TYPE_PARAFOIL = 28,
/// <summary>
/// Dodecarotor
/// </summary>
MAV_TYPE_DODECAROTOR = 29,
/// <summary>
/// Camera
/// </summary>
MAV_TYPE_CAMERA = 30,
/// <summary>
/// Charging station
/// </summary>
MAV_TYPE_CHARGING_STATION = 31,
MAV_TYPE_ENUM_END = 32,
}
/// <summary>
/// These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65.
/// </summary>
public enum FIRMWARE_VERSION_TYPE : uint
{
/// <summary>
/// development release
/// </summary>
FIRMWARE_VERSION_TYPE_DEV = 0,
/// <summary>
/// alpha release
/// </summary>
FIRMWARE_VERSION_TYPE_ALPHA = 64,
/// <summary>
/// beta release
/// </summary>
FIRMWARE_VERSION_TYPE_BETA = 128,
/// <summary>
/// release candidate
/// </summary>
FIRMWARE_VERSION_TYPE_RC = 192,
/// <summary>
/// official stable release
/// </summary>
FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
FIRMWARE_VERSION_TYPE_ENUM_END = 256,
}
/// <summary>
/// Flags to report failure cases over the high latency telemtry.
/// </summary>
public enum HL_FAILURE_FLAG : uint
{
/// <summary>
/// GPS failure.
/// </summary>
HL_FAILURE_FLAG_GPS = 1,
/// <summary>
/// Differential pressure sensor failure.
/// </summary>
HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2,
/// <summary>
/// Absolute pressure sensor failure.
/// </summary>
HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4,
/// <summary>
/// Accelerometer sensor failure.
/// </summary>
HL_FAILURE_FLAG_3D_ACCEL = 8,
/// <summary>
/// Gyroscope sensor failure.
/// </summary>
HL_FAILURE_FLAG_3D_GYRO = 16,
/// <summary>
/// Magnetometer sensor failure.
/// </summary>
HL_FAILURE_FLAG_3D_MAG = 32,
/// <summary>
/// Terrain subsystem failure.
/// </summary>
HL_FAILURE_FLAG_TERRAIN = 64,
/// <summary>
/// Battery failure/critical low battery.
/// </summary>
HL_FAILURE_FLAG_BATTERY = 128,
/// <summary>
/// RC receiver failure/no rc connection.
/// </summary>
HL_FAILURE_FLAG_RC_RECEIVER = 256,
/// <summary>
/// Offboard link failure.
/// </summary>
HL_FAILURE_FLAG_OFFBOARD_LINK = 512,
/// <summary>
/// Engine failure.
/// </summary>
HL_FAILURE_FLAG_ENGINE = 1024,
/// <summary>
/// Geofence violation.
/// </summary>
HL_FAILURE_FLAG_GEOFENCE = 2048,
/// <summary>
/// Estimator failure, for example measurement rejection or large variances.
/// </summary>
HL_FAILURE_FLAG_ESTIMATOR = 4096,
/// <summary>
/// Mission failure.
/// </summary>
HL_FAILURE_FLAG_MISSION = 8192,
HL_FAILURE_FLAG_ENUM_END = 8193,
}
/// <summary>
/// These flags encode the MAV mode.
/// </summary>
public enum MAV_MODE_FLAG : uint
{
/// <summary>
/// 0b00000001 Reserved for future use.
/// </summary>
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1,
/// <summary>
/// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
/// </summary>
MAV_MODE_FLAG_TEST_ENABLED = 2,
/// <summary>
/// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
/// </summary>
MAV_MODE_FLAG_AUTO_ENABLED = 4,
/// <summary>
/// 0b00001000 guided mode enabled, system flies waypoints / mission items.
/// </summary>
MAV_MODE_FLAG_GUIDED_ENABLED = 8,
/// <summary>
/// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
/// </summary>
MAV_MODE_FLAG_STABILIZE_ENABLED = 16,
/// <summary>
/// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
/// </summary>
MAV_MODE_FLAG_HIL_ENABLED = 32,
/// <summary>
/// 0b01000000 remote control input is enabled.
/// </summary>
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
/// <summary>
/// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state.
/// </summary>
MAV_MODE_FLAG_SAFETY_ARMED = 128,
MAV_MODE_FLAG_ENUM_END = 129,
}
/// <summary>
/// These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.
/// </summary>
public enum MAV_MODE_FLAG_DECODE_POSITION : uint
{
/// <summary>
/// Eighth bit: 00000001
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
/// <summary>
/// Seventh bit: 00000010
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
/// <summary>
/// Sixt bit: 00000100
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
/// <summary>
/// Fifth bit: 00001000
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
/// <summary>
/// Fourth bit: 00010000
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
/// <summary>
/// Third bit: 00100000
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
/// <summary>
/// Second bit: 01000000
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
/// <summary>
/// First bit: 10000000
/// </summary>
MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
MAV_MODE_FLAG_DECODE_POSITION_ENUM_END = 129,
}
/// <summary>
/// Override command, pauses current mission execution and moves immediately to a position
/// </summary>
public enum MAV_GOTO : uint
{
/// <summary>
/// Hold at the current position.
/// </summary>
MAV_GOTO_DO_HOLD = 0,
/// <summary>
/// Continue with the next item in mission execution.
/// </summary>
MAV_GOTO_DO_CONTINUE = 1,
/// <summary>
/// Hold at the current position of the system
/// </summary>
MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
/// <summary>
/// Hold at the position specified in the parameters of the DO_HOLD action
/// </summary>
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
MAV_GOTO_ENUM_END = 4,
}
/// <summary>
/// These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
/// simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.
/// </summary>
public enum MAV_MODE : uint
{
/// <summary>
/// System is not ready to fly, booting, calibrating, etc. No flag is set.
/// </summary>
MAV_MODE_PREFLIGHT = 0,
/// <summary>
/// System is allowed to be active, under manual (RC) control, no stabilization
/// </summary>
MAV_MODE_MANUAL_DISARMED = 64,
/// <summary>
/// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
/// </summary>
MAV_MODE_TEST_DISARMED = 66,
/// <summary>
/// System is allowed to be active, under assisted RC control.
/// </summary>
MAV_MODE_STABILIZE_DISARMED = 80,
/// <summary>
/// System is allowed to be active, under autonomous control, manual setpoint
/// </summary>
MAV_MODE_GUIDED_DISARMED = 88,
/// <summary>
/// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
/// </summary>
MAV_MODE_AUTO_DISARMED = 92,
/// <summary>
/// System is allowed to be active, under manual (RC) control, no stabilization
/// </summary>
MAV_MODE_MANUAL_ARMED = 192,
/// <summary>
/// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
/// </summary>
MAV_MODE_TEST_ARMED = 194,
/// <summary>
/// System is allowed to be active, under assisted RC control.
/// </summary>
MAV_MODE_STABILIZE_ARMED = 208,
/// <summary>
/// System is allowed to be active, under autonomous control, manual setpoint
/// </summary>
MAV_MODE_GUIDED_ARMED = 216,
/// <summary>
/// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)
/// </summary>
MAV_MODE_AUTO_ARMED = 220,
MAV_MODE_ENUM_END = 221,
}
/// <summary>
///
/// </summary>
public enum MAV_STATE : uint
{
/// <summary>
/// Uninitialized system, state is unknown.
/// </summary>
MAV_STATE_UNINIT = 0,
/// <summary>
/// System is booting up.
/// </summary>
MAV_STATE_BOOT = 1,
/// <summary>
/// System is calibrating and not flight-ready.
/// </summary>
MAV_STATE_CALIBRATING = 2,
/// <summary>
/// System is grounded and on standby. It can be launched any time.
/// </summary>
MAV_STATE_STANDBY = 3,
/// <summary>
/// System is active and might be already airborne. Motors are engaged.
/// </summary>
MAV_STATE_ACTIVE = 4,
/// <summary>
/// System is in a non-normal flight mode. It can however still navigate.
/// </summary>
MAV_STATE_CRITICAL = 5,
/// <summary>
/// System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.
/// </summary>
MAV_STATE_EMERGENCY = 6,
/// <summary>
/// System just initialized its power-down sequence, will shut down now.
/// </summary>
MAV_STATE_POWEROFF = 7,
/// <summary>
/// System is terminating itself.
/// </summary>
MAV_STATE_FLIGHT_TERMINATION = 8,
MAV_STATE_ENUM_END = 9,
}
/// <summary>
///
/// </summary>
public enum MAV_COMPONENT : uint
{
MAV_COMP_ID_ALL = 0,
MAV_COMP_ID_AUTOPILOT1 = 1,
MAV_COMP_ID_CAMERA = 100,
MAV_COMP_ID_CAMERA2 = 101,
MAV_COMP_ID_CAMERA3 = 102,
MAV_COMP_ID_CAMERA4 = 103,
MAV_COMP_ID_CAMERA5 = 104,
MAV_COMP_ID_CAMERA6 = 105,
MAV_COMP_ID_SERVO1 = 140,
MAV_COMP_ID_SERVO2 = 141,
MAV_COMP_ID_SERVO3 = 142,
MAV_COMP_ID_SERVO4 = 143,
MAV_COMP_ID_SERVO5 = 144,
MAV_COMP_ID_SERVO6 = 145,
MAV_COMP_ID_SERVO7 = 146,
MAV_COMP_ID_SERVO8 = 147,
MAV_COMP_ID_SERVO9 = 148,
MAV_COMP_ID_SERVO10 = 149,
MAV_COMP_ID_SERVO11 = 150,
MAV_COMP_ID_SERVO12 = 151,
MAV_COMP_ID_SERVO13 = 152,
MAV_COMP_ID_SERVO14 = 153,
MAV_COMP_ID_GIMBAL = 154,
MAV_COMP_ID_LOG = 155,
MAV_COMP_ID_ADSB = 156,
/// <summary>
/// On Screen Display (OSD) devices for video links
/// </summary>
MAV_COMP_ID_OSD = 157,
/// <summary>
/// Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol
/// </summary>
MAV_COMP_ID_PERIPHERAL = 158,
MAV_COMP_ID_QX1_GIMBAL = 159,
MAV_COMP_ID_MAPPER = 180,
MAV_COMP_ID_MISSIONPLANNER = 190,
MAV_COMP_ID_PATHPLANNER = 195,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
MAV_COMP_ID_GPS = 220,
MAV_COMP_ID_GPS2 = 221,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250,
MAV_COMPONENT_ENUM_END = 251,
}
/// <summary>
/// These encode the sensors whose status is sent as part of the SYS_STATUS message.
/// </summary>
public enum MAV_SYS_STATUS_SENSOR : uint
{
/// <summary>
/// 0x01 3D gyro
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_GYRO = 1,
/// <summary>
/// 0x02 3D accelerometer
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2,
/// <summary>
/// 0x04 3D magnetometer
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_MAG = 4,
/// <summary>
/// 0x08 absolute pressure
/// </summary>
MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8,
/// <summary>
/// 0x10 differential pressure
/// </summary>
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16,
/// <summary>
/// 0x20 GPS
/// </summary>
MAV_SYS_STATUS_SENSOR_GPS = 32,
/// <summary>
/// 0x40 optical flow
/// </summary>
MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64,
/// <summary>
/// 0x80 computer vision position
/// </summary>
MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128,
/// <summary>
/// 0x100 laser based position
/// </summary>
MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256,
/// <summary>
/// 0x200 external ground truth (Vicon or Leica)
/// </summary>
MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512,
/// <summary>
/// 0x400 3D angular rate control
/// </summary>
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024,
/// <summary>
/// 0x800 attitude stabilization
/// </summary>
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048,
/// <summary>
/// 0x1000 yaw position
/// </summary>
MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096,
/// <summary>
/// 0x2000 z/altitude control
/// </summary>
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192,
/// <summary>
/// 0x4000 x/y position control
/// </summary>
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384,
/// <summary>
/// 0x8000 motor outputs / control
/// </summary>
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768,
/// <summary>
/// 0x10000 rc receiver
/// </summary>
MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536,
/// <summary>
/// 0x20000 2nd 3D gyro
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072,
/// <summary>
/// 0x40000 2nd 3D accelerometer
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144,
/// <summary>
/// 0x80000 2nd 3D magnetometer
/// </summary>
MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288,
/// <summary>
/// 0x100000 geofence
/// </summary>
MAV_SYS_STATUS_GEOFENCE = 1048576,
/// <summary>
/// 0x200000 AHRS subsystem health
/// </summary>
MAV_SYS_STATUS_AHRS = 2097152,
/// <summary>
/// 0x400000 Terrain subsystem health
/// </summary>
MAV_SYS_STATUS_TERRAIN = 4194304,
/// <summary>
/// 0x800000 Motors are reversed
/// </summary>
MAV_SYS_STATUS_REVERSE_MOTOR = 8388608,
/// <summary>
/// 0x1000000 Logging
/// </summary>
MAV_SYS_STATUS_LOGGING = 16777216,
/// <summary>
/// 0x2000000 Battery
/// </summary>
MAV_SYS_STATUS_SENSOR_BATTERY = 33554432,
MAV_SYS_STATUS_SENSOR_ENUM_END = 33554433,
}
/// <summary>
///
/// </summary>
public enum MAV_FRAME : uint
{
/// <summary>
/// Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
/// </summary>
MAV_FRAME_GLOBAL = 0,
/// <summary>
/// Local coordinate frame, Z-down (x: north, y: east, z: down).
/// </summary>
MAV_FRAME_LOCAL_NED = 1,
/// <summary>
/// NOT a coordinate frame, indicates a mission command.
/// </summary>
MAV_FRAME_MISSION = 2,
/// <summary>
/// Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.
/// </summary>
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
/// <summary>
/// Local coordinate frame, Z-up (x: east, y: north, z: up).
/// </summary>
MAV_FRAME_LOCAL_ENU = 4,
/// <summary>
/// Global coordinate frame, WGS84 coordinate system. First value / x: latitude in degrees*1.0e-7, second value / y: longitude in degrees*1.0e-7, third value / z: positive altitude over mean sea level (MSL).
/// </summary>
MAV_FRAME_GLOBAL_INT = 5,
/// <summary>
/// Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude with 0 being at the altitude of the home location.
/// </summary>
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
/// <summary>
/// Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.
/// </summary>
MAV_FRAME_LOCAL_OFFSET_NED = 7,
/// <summary>
/// Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.
/// </summary>
MAV_FRAME_BODY_NED = 8,
/// <summary>
/// Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.
/// </summary>
MAV_FRAME_BODY_OFFSET_NED = 9,
/// <summary>
/// Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
/// </summary>
MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
/// <summary>
/// Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees*10e-7, second value / y: longitude in degrees*10e-7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
/// </summary>
MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
/// <summary>
/// Body fixed frame of reference, Z-down (x: forward, y: right, z: down).
/// </summary>
MAV_FRAME_BODY_FRD = 12,
/// <summary>
/// Body fixed frame of reference, Z-up (x: forward, y: left, z: up).
/// </summary>
MAV_FRAME_BODY_FLU = 13,
/// <summary>
/// Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down).
/// </summary>
MAV_FRAME_MOCAP_NED = 14,
/// <summary>
/// Odometry local coordinate frame of data given by a motion capture system, Z-up (x: east, y: north, z: up).
/// </summary>
MAV_FRAME_MOCAP_ENU = 15,
/// <summary>
/// Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: north, y: east, z: down).
/// </summary>
MAV_FRAME_VISION_NED = 16,
/// <summary>
/// Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: east, y: north, z: up).
/// </summary>
MAV_FRAME_VISION_ENU = 17,
/// <summary>
/// Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: north, y: east, z: down).
/// </summary>
MAV_FRAME_ESTIM_NED = 18,
/// <summary>
/// Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: east, y: noth, z: up).
/// </summary>
MAV_FRAME_ESTIM_ENU = 19,
MAV_FRAME_ENUM_END = 20,
}
/// <summary>
///
/// </summary>
public enum MAVLINK_DATA_STREAM_TYPE : uint
{
MAVLINK_DATA_STREAM_IMG_JPEG = 1,
MAVLINK_DATA_STREAM_IMG_BMP = 2,
MAVLINK_DATA_STREAM_IMG_RAW8U = 3,
MAVLINK_DATA_STREAM_IMG_RAW32U = 4,
MAVLINK_DATA_STREAM_IMG_PGM = 5,
MAVLINK_DATA_STREAM_IMG_PNG = 6,
MAVLINK_DATA_STREAM_TYPE_ENUM_END = 7,
}
/// <summary>
///
/// </summary>
public enum FENCE_ACTION : uint
{
/// <summary>
/// Disable fenced mode
/// </summary>
FENCE_ACTION_NONE = 0,
/// <summary>
/// Switched to guided mode to return point (fence point 0)
/// </summary>
FENCE_ACTION_GUIDED = 1,