forked from ungerik/go-mavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
messages.go
2281 lines (1986 loc) · 92.1 KB
/
messages.go
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
package mavlink
type newMessageFunc func() Message
type Message interface {
ID() uint8
Size() uint8
}
var messageFactory = map[uint8]newMessageFunc{
0: func() Message { return new(Heartbeat) },
1: func() Message { return new(SysStatus) },
2: func() Message { return new(SystemTime) },
4: func() Message { return new(Ping) },
5: func() Message { return new(ChangeOperatorControl) },
6: func() Message { return new(ChangeOperatorControlAck) },
7: func() Message { return new(AuthKey) },
11: func() Message { return new(SetMode) },
20: func() Message { return new(ParamRequestRead) },
21: func() Message { return new(ParamRequestList) },
22: func() Message { return new(ParamValue) },
23: func() Message { return new(ParamSet) },
24: func() Message { return new(GpsRawInt) },
25: func() Message { return new(GpsStatus) },
26: func() Message { return new(ScaledImu) },
27: func() Message { return new(RawImu) },
28: func() Message { return new(RawPressure) },
29: func() Message { return new(ScaledPressure) },
30: func() Message { return new(Attitude) },
31: func() Message { return new(AttitudeQuaternion) },
32: func() Message { return new(LocalPositionNed) },
33: func() Message { return new(GlobalPositionInt) },
34: func() Message { return new(RcChannelsScaled) },
35: func() Message { return new(RcChannelsRaw) },
36: func() Message { return new(ServoOutputRaw) },
37: func() Message { return new(MissionRequestPartialList) },
38: func() Message { return new(MissionWritePartialList) },
39: func() Message { return new(MissionItem) },
40: func() Message { return new(MissionRequest) },
41: func() Message { return new(MissionSetCurrent) },
42: func() Message { return new(MissionCurrent) },
43: func() Message { return new(MissionRequestList) },
44: func() Message { return new(MissionCount) },
45: func() Message { return new(MissionClearAll) },
46: func() Message { return new(MissionItemReached) },
47: func() Message { return new(MissionAck) },
48: func() Message { return new(SetGpsGlobalOrigin) },
49: func() Message { return new(GpsGlobalOrigin) },
50: func() Message { return new(SetLocalPositionSetpoint) },
51: func() Message { return new(LocalPositionSetpoint) },
52: func() Message { return new(GlobalPositionSetpointInt) },
53: func() Message { return new(SetGlobalPositionSetpointInt) },
54: func() Message { return new(SafetySetAllowedArea) },
55: func() Message { return new(SafetyAllowedArea) },
56: func() Message { return new(SetRollPitchYawThrust) },
57: func() Message { return new(SetRollPitchYawSpeedThrust) },
58: func() Message { return new(RollPitchYawThrustSetpoint) },
59: func() Message { return new(RollPitchYawSpeedThrustSetpoint) },
60: func() Message { return new(SetQuadMotorsSetpoint) },
61: func() Message { return new(SetQuadSwarmRollPitchYawThrust) },
62: func() Message { return new(NavControllerOutput) },
63: func() Message { return new(SetQuadSwarmLedRollPitchYawThrust) },
64: func() Message { return new(StateCorrection) },
66: func() Message { return new(RequestDataStream) },
67: func() Message { return new(DataStream) },
69: func() Message { return new(ManualControl) },
70: func() Message { return new(RcChannelsOverride) },
74: func() Message { return new(VfrHud) },
76: func() Message { return new(CommandLong) },
77: func() Message { return new(CommandAck) },
80: func() Message { return new(RollPitchYawRatesThrustSetpoint) },
81: func() Message { return new(ManualSetpoint) },
89: func() Message { return new(LocalPositionNedSystemGlobalOffset) },
90: func() Message { return new(HilState) },
91: func() Message { return new(HilControls) },
92: func() Message { return new(HilRcInputsRaw) },
100: func() Message { return new(OpticalFlow) },
101: func() Message { return new(GlobalVisionPositionEstimate) },
102: func() Message { return new(VisionPositionEstimate) },
103: func() Message { return new(VisionSpeedEstimate) },
104: func() Message { return new(ViconPositionEstimate) },
105: func() Message { return new(HighresImu) },
106: func() Message { return new(OmnidirectionalFlow) },
107: func() Message { return new(HilSensor) },
108: func() Message { return new(SimState) },
109: func() Message { return new(RadioStatus) },
110: func() Message { return new(FileTransferStart) },
111: func() Message { return new(FileTransferDirList) },
112: func() Message { return new(FileTransferRes) },
113: func() Message { return new(HilGps) },
114: func() Message { return new(HilOpticalFlow) },
115: func() Message { return new(HilStateQuaternion) },
147: func() Message { return new(BatteryStatus) },
148: func() Message { return new(Setpoint8dof) },
149: func() Message { return new(Setpoint6dof) },
249: func() Message { return new(MemoryVect) },
250: func() Message { return new(DebugVect) },
251: func() Message { return new(NamedValueFloat) },
252: func() Message { return new(NamedValueInt) },
253: func() Message { return new(Statustext) },
254: func() Message { return new(Debug) },
}
// Micro air vehicle / autopilot classes. This identifies the individual model.
const (
// Generic autopilot, full support for everything
MAV_AUTOPILOT_GENERIC = 0
// PIXHAWK autopilot, http://pixhawk.ethz.ch
MAV_AUTOPILOT_PIXHAWK = 1
// SLUGS autopilot, http://slugsuav.soe.ucsc.edu
MAV_AUTOPILOT_SLUGS = 2
// ArduPilotMega / ArduCopter, http://diydrones.com
MAV_AUTOPILOT_ARDUPILOTMEGA = 3
// OpenPilot, http://openpilot.org
MAV_AUTOPILOT_OPENPILOT = 4
// Generic autopilot only supporting simple waypoints
MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5
// Generic autopilot supporting waypoints and other simple navigation commands
MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6
// Generic autopilot supporting the full mission command set
MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7
// No valid autopilot, e.g. a GCS or other MAVLink component
MAV_AUTOPILOT_INVALID = 8
// PPZ UAV - http://nongnu.org/paparazzi
MAV_AUTOPILOT_PPZ = 9
// UAV Dev Board
MAV_AUTOPILOT_UDB = 10
// FlexiPilot
MAV_AUTOPILOT_FP = 11
// PX4 Autopilot - http://pixhawk.ethz.ch/px4/
MAV_AUTOPILOT_PX4 = 12
// SMACCMPilot - http://smaccmpilot.org
MAV_AUTOPILOT_SMACCMPILOT = 13
// AutoQuad -- http://autoquad.org
MAV_AUTOPILOT_AUTOQUAD = 14
// Armazila -- http://armazila.com
MAV_AUTOPILOT_ARMAZILA = 15
// Aerob -- http://aerob.ru
MAV_AUTOPILOT_AEROB = 16
)
const (
// Generic micro air vehicle.
MAV_TYPE_GENERIC = 0
// Fixed wing aircraft.
MAV_TYPE_FIXED_WING = 1
// Quadrotor
MAV_TYPE_QUADROTOR = 2
// Coaxial helicopter
MAV_TYPE_COAXIAL = 3
// Normal helicopter with tail rotor.
MAV_TYPE_HELICOPTER = 4
// Ground installation
MAV_TYPE_ANTENNA_TRACKER = 5
// Operator control unit / ground control station
MAV_TYPE_GCS = 6
// Airship, controlled
MAV_TYPE_AIRSHIP = 7
// Free balloon, uncontrolled
MAV_TYPE_FREE_BALLOON = 8
// Rocket
MAV_TYPE_ROCKET = 9
// Ground rover
MAV_TYPE_GROUND_ROVER = 10
// Surface vessel, boat, ship
MAV_TYPE_SURFACE_BOAT = 11
// Submarine
MAV_TYPE_SUBMARINE = 12
// Hexarotor
MAV_TYPE_HEXAROTOR = 13
// Octorotor
MAV_TYPE_OCTOROTOR = 14
// Octorotor
MAV_TYPE_TRICOPTER = 15
// Flapping wing
MAV_TYPE_FLAPPING_WING = 16
// Flapping wing
MAV_TYPE_KITE = 17
)
// These flags encode the MAV mode.
const (
// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.
MAV_MODE_FLAG_SAFETY_ARMED = 128
// 0b01000000 remote control input is enabled.
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64
// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
MAV_MODE_FLAG_HIL_ENABLED = 32
// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
MAV_MODE_FLAG_STABILIZE_ENABLED = 16
// 0b00001000 guided mode enabled, system flies MISSIONs / mission items.
MAV_MODE_FLAG_GUIDED_ENABLED = 8
// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
MAV_MODE_FLAG_AUTO_ENABLED = 4
// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
MAV_MODE_FLAG_TEST_ENABLED = 2
// 0b00000001 Reserved for future use.
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
)
// 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.
const (
// First bit: 10000000
MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128
// Second bit: 01000000
MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64
// Third bit: 00100000
MAV_MODE_FLAG_DECODE_POSITION_HIL = 32
// Fourth bit: 00010000
MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16
// Fifth bit: 00001000
MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8
// Sixt bit: 00000100
MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4
// Seventh bit: 00000010
MAV_MODE_FLAG_DECODE_POSITION_TEST = 2
// Eighth bit: 00000001
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1
)
// Override command, pauses current mission execution and moves immediately to a position
const (
// Hold at the current position.
MAV_GOTO_DO_HOLD = 0
// Continue with the next item in mission execution.
MAV_GOTO_DO_CONTINUE = 1
// Hold at the current position of the system
MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2
// Hold at the position specified in the parameters of the DO_HOLD action
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3
)
// 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.
const (
// System is not ready to fly, booting, calibrating, etc. No flag is set.
MAV_MODE_PREFLIGHT = 0
// System is allowed to be active, under assisted RC control.
MAV_MODE_STABILIZE_DISARMED = 80
// System is allowed to be active, under assisted RC control.
MAV_MODE_STABILIZE_ARMED = 208
// System is allowed to be active, under manual (RC) control, no stabilization
MAV_MODE_MANUAL_DISARMED = 64
// System is allowed to be active, under manual (RC) control, no stabilization
MAV_MODE_MANUAL_ARMED = 192
// System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_GUIDED_DISARMED = 88
// System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_GUIDED_ARMED = 216
// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
MAV_MODE_AUTO_DISARMED = 92
// System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
MAV_MODE_AUTO_ARMED = 220
// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
MAV_MODE_TEST_DISARMED = 66
// UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
MAV_MODE_TEST_ARMED = 194
)
const (
// Uninitialized system, state is unknown.
MAV_STATE_UNINIT = 0
// System is booting up.
MAV_STATE_BOOT = 1
// System is calibrating and not flight-ready.
MAV_STATE_CALIBRATING = 2
// System is grounded and on standby. It can be launched any time.
MAV_STATE_STANDBY = 3
// System is active and might be already airborne. Motors are engaged.
MAV_STATE_ACTIVE = 4
// System is in a non-normal flight mode. It can however still navigate.
MAV_STATE_CRITICAL = 5
// 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.
MAV_STATE_EMERGENCY = 6
// System just initialized its power-down sequence, will shut down now.
MAV_STATE_POWEROFF = 7
)
const (
MAV_COMP_ID_ALL = 0
MAV_COMP_ID_GPS = 220
MAV_COMP_ID_MISSIONPLANNER = 190
MAV_COMP_ID_PATHPLANNER = 195
MAV_COMP_ID_MAPPER = 180
MAV_COMP_ID_CAMERA = 100
MAV_COMP_ID_IMU = 200
MAV_COMP_ID_IMU_2 = 201
MAV_COMP_ID_IMU_3 = 202
MAV_COMP_ID_UDP_BRIDGE = 240
MAV_COMP_ID_UART_BRIDGE = 241
MAV_COMP_ID_SYSTEM_CONTROL = 250
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
)
// These encode the sensors whose status is sent as part of the SYS_STATUS message.
const (
// 0x01 3D gyro
MAV_SYS_STATUS_SENSOR_3D_GYRO = 1
// 0x02 3D accelerometer
MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2
// 0x04 3D magnetometer
MAV_SYS_STATUS_SENSOR_3D_MAG = 4
// 0x08 absolute pressure
MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8
// 0x10 differential pressure
MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16
// 0x20 GPS
MAV_SYS_STATUS_SENSOR_GPS = 32
// 0x40 optical flow
MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64
// 0x80 computer vision position
MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128
// 0x100 laser based position
MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256
// 0x200 external ground truth (Vicon or Leica)
MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512
// 0x400 3D angular rate control
MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024
// 0x800 attitude stabilization
MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048
// 0x1000 yaw position
MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096
// 0x2000 z/altitude control
MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192
// 0x4000 x/y position control
MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384
// 0x8000 motor outputs / control
MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768
// 0x10000 rc receiver
MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536
)
const (
// Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)
MAV_FRAME_GLOBAL = 0
// Local coordinate frame, Z-up (x: north, y: east, z: down).
MAV_FRAME_LOCAL_NED = 1
// NOT a coordinate frame, indicates a mission command.
MAV_FRAME_MISSION = 2
// 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.
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3
// Local coordinate frame, Z-down (x: east, y: north, z: up)
MAV_FRAME_LOCAL_ENU = 4
)
const (
MAVLINK_DATA_STREAM_IMG_JPEG = iota
MAVLINK_DATA_STREAM_IMG_BMP
MAVLINK_DATA_STREAM_IMG_RAW8U
MAVLINK_DATA_STREAM_IMG_RAW32U
MAVLINK_DATA_STREAM_IMG_PGM
MAVLINK_DATA_STREAM_IMG_PNG
)
// Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.
const (
// Navigate to MISSION.
MAV_CMD_NAV_WAYPOINT = 16
// Loiter around this MISSION an unlimited amount of time
MAV_CMD_NAV_LOITER_UNLIM = 17
// Loiter around this MISSION for X turns
MAV_CMD_NAV_LOITER_TURNS = 18
// Loiter around this MISSION for X seconds
MAV_CMD_NAV_LOITER_TIME = 19
// Return to launch location
MAV_CMD_NAV_RETURN_TO_LAUNCH = 20
// Land at location
MAV_CMD_NAV_LAND = 21
// Takeoff from ground / hand
MAV_CMD_NAV_TAKEOFF = 22
// Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.
MAV_CMD_NAV_ROI = 80
// Control autonomous path planning on the MAV.
MAV_CMD_NAV_PATHPLANNING = 81
// NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration
MAV_CMD_NAV_LAST = 95
// Delay mission state machine.
MAV_CMD_CONDITION_DELAY = 112
// Ascend/descend at rate. Delay mission state machine until desired altitude reached.
MAV_CMD_CONDITION_CHANGE_ALT = 113
// Delay mission state machine until within desired distance of next NAV point.
MAV_CMD_CONDITION_DISTANCE = 114
// Reach a certain target angle.
MAV_CMD_CONDITION_YAW = 115
// NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration
MAV_CMD_CONDITION_LAST = 159
// Set system mode.
MAV_CMD_DO_SET_MODE = 176
// Jump to the desired command in the mission list. Repeat this action only the specified number of times
MAV_CMD_DO_JUMP = 177
// Change speed and/or throttle set points.
MAV_CMD_DO_CHANGE_SPEED = 178
// Changes the home location either to the current location or a specified location.
MAV_CMD_DO_SET_HOME = 179
// Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.
MAV_CMD_DO_SET_PARAMETER = 180
// Set a relay to a condition.
MAV_CMD_DO_SET_RELAY = 181
// Cycle a relay on and off for a desired number of cyles with a desired period.
MAV_CMD_DO_REPEAT_RELAY = 182
// Set a servo to a desired PWM value.
MAV_CMD_DO_SET_SERVO = 183
// Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.
MAV_CMD_DO_REPEAT_SERVO = 184
// Control onboard camera system.
MAV_CMD_DO_CONTROL_VIDEO = 200
// Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.
MAV_CMD_DO_SET_ROI = 201
// NOP - This command is only used to mark the upper limit of the DO commands in the enumeration
MAV_CMD_DO_LAST = 240
// Trigger calibration. This command will be only accepted if in pre-flight mode.
MAV_CMD_PREFLIGHT_CALIBRATION = 241
// Set sensor offsets. This command will be only accepted if in pre-flight mode.
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242
// Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.
MAV_CMD_PREFLIGHT_STORAGE = 245
// Request the reboot or shutdown of system components.
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246
// Hold / continue the current action
MAV_CMD_OVERRIDE_GOTO = 252
// start running a mission
MAV_CMD_MISSION_START = 300
// Arms / Disarms a component
MAV_CMD_COMPONENT_ARM_DISARM = 400
// Starts receiver pairing
MAV_CMD_START_RX_PAIR = 500
)
// Data stream IDs. A data stream is not a fixed set of messages, but rather a
// recommendation to the autopilot software. Individual autopilots may or may not obey
// the recommended messages.
const (
// Enable all data streams
MAV_DATA_STREAM_ALL = 0
// Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
MAV_DATA_STREAM_RAW_SENSORS = 1
// Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
MAV_DATA_STREAM_EXTENDED_STATUS = 2
// Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
MAV_DATA_STREAM_RC_CHANNELS = 3
// Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
MAV_DATA_STREAM_RAW_CONTROLLER = 4
// Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
MAV_DATA_STREAM_POSITION = 6
// Dependent on the autopilot
MAV_DATA_STREAM_EXTRA1 = 10
// Dependent on the autopilot
MAV_DATA_STREAM_EXTRA2 = 11
// Dependent on the autopilot
MAV_DATA_STREAM_EXTRA3 = 12
)
// The ROI (region of interest) for the vehicle. This can be
// be used by the vehicle for camera/vehicle attitude alignment (see
// MAV_CMD_NAV_ROI).
const (
// No region of interest.
MAV_ROI_NONE = 0
// Point toward next MISSION.
MAV_ROI_WPNEXT = 1
// Point toward given MISSION.
MAV_ROI_WPINDEX = 2
// Point toward fixed location.
MAV_ROI_LOCATION = 3
// Point toward of given id.
MAV_ROI_TARGET = 4
)
// ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.
const (
// Command / mission item is ok.
MAV_CMD_ACK_OK = iota
// Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.
MAV_CMD_ACK_ERR_FAIL
// The system is refusing to accept this command from this source / communication partner.
MAV_CMD_ACK_ERR_ACCESS_DENIED
// Command or mission item is not supported, other commands would be accepted.
MAV_CMD_ACK_ERR_NOT_SUPPORTED
// The coordinate frame of this command / mission item is not supported.
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED
// The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE
// The X or latitude value is out of range.
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE
// The Y or longitude value is out of range.
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE
// The Z or altitude value is out of range.
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE
)
// Specifies the datatype of a MAVLink parameter.
const (
// 8-bit unsigned integer
MAV_PARAM_TYPE_UINT8 = 1
// 8-bit signed integer
MAV_PARAM_TYPE_INT8 = 2
// 16-bit unsigned integer
MAV_PARAM_TYPE_UINT16 = 3
// 16-bit signed integer
MAV_PARAM_TYPE_INT16 = 4
// 32-bit unsigned integer
MAV_PARAM_TYPE_UINT32 = 5
// 32-bit signed integer
MAV_PARAM_TYPE_INT32 = 6
// 64-bit unsigned integer
MAV_PARAM_TYPE_UINT64 = 7
// 64-bit signed integer
MAV_PARAM_TYPE_INT64 = 8
// 32-bit floating-point
MAV_PARAM_TYPE_REAL32 = 9
// 64-bit floating-point
MAV_PARAM_TYPE_REAL64 = 10
)
// result from a mavlink command
const (
// Command ACCEPTED and EXECUTED
MAV_RESULT_ACCEPTED = 0
// Command TEMPORARY REJECTED/DENIED
MAV_RESULT_TEMPORARILY_REJECTED = 1
// Command PERMANENTLY DENIED
MAV_RESULT_DENIED = 2
// Command UNKNOWN/UNSUPPORTED
MAV_RESULT_UNSUPPORTED = 3
// Command executed, but failed
MAV_RESULT_FAILED = 4
)
// result in a mavlink mission ack
const (
// mission accepted OK
MAV_MISSION_ACCEPTED = 0
// generic error / not accepting mission commands at all right now
MAV_MISSION_ERROR = 1
// coordinate frame is not supported
MAV_MISSION_UNSUPPORTED_FRAME = 2
// command is not supported
MAV_MISSION_UNSUPPORTED = 3
// mission item exceeds storage space
MAV_MISSION_NO_SPACE = 4
// one of the parameters has an invalid value
MAV_MISSION_INVALID = 5
// param1 has an invalid value
MAV_MISSION_INVALID_PARAM1 = 6
// param2 has an invalid value
MAV_MISSION_INVALID_PARAM2 = 7
// param3 has an invalid value
MAV_MISSION_INVALID_PARAM3 = 8
// param4 has an invalid value
MAV_MISSION_INVALID_PARAM4 = 9
// x/param5 has an invalid value
MAV_MISSION_INVALID_PARAM5_X = 10
// y/param6 has an invalid value
MAV_MISSION_INVALID_PARAM6_Y = 11
// param7 has an invalid value
MAV_MISSION_INVALID_PARAM7 = 12
// received waypoint out of sequence
MAV_MISSION_INVALID_SEQUENCE = 13
// not accepting any mission commands from this communication partner
MAV_MISSION_DENIED = 14
)
// Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.
const (
// System is unusable. This is a "panic" condition.
MAV_SEVERITY_EMERGENCY = 0
// Action should be taken immediately. Indicates error in non-critical systems.
MAV_SEVERITY_ALERT = 1
// Action must be taken immediately. Indicates failure in a primary system.
MAV_SEVERITY_CRITICAL = 2
// Indicates an error in secondary/redundant systems.
MAV_SEVERITY_ERROR = 3
// Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.
MAV_SEVERITY_WARNING = 4
// An unusual event has occured, though not an error condition. This should be investigated for the root cause.
MAV_SEVERITY_NOTICE = 5
// Normal operational messages. Useful for logging. No action is required for these messages.
MAV_SEVERITY_INFO = 6
// Useful non-operational messages that can assist in debugging. These should not occur during normal operation.
MAV_SEVERITY_DEBUG = 7
)
// The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).
type Heartbeat struct {
CustomMode uint32 // A bitfield for use for autopilot-specific flags.
Type uint8 // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
Autopilot uint8 // Autopilot type / class. defined in MAV_AUTOPILOT ENUM
BaseMode uint8 // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
SystemStatus uint8 // System status flag, see MAV_STATE ENUM
MavlinkVersion uint8 // MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
}
func (self *Heartbeat) ID() uint8 {
return 0
}
func (self *Heartbeat) Size() uint8 {
return 9
}
// The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.
type SysStatus struct {
OnboardControlSensorsPresent uint32 // Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
OnboardControlSensorsEnabled uint32 // Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
OnboardControlSensorsHealth uint32 // Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR
Load uint16 // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
VoltageBattery uint16 // Battery voltage, in millivolts (1 = 1 millivolt)
CurrentBattery int16 // Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
DropRateComm uint16 // Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
ErrorsComm uint16 // Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
ErrorsCount1 uint16 // Autopilot-specific errors
ErrorsCount2 uint16 // Autopilot-specific errors
ErrorsCount3 uint16 // Autopilot-specific errors
ErrorsCount4 uint16 // Autopilot-specific errors
BatteryRemaining int8 // Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
}
func (self *SysStatus) ID() uint8 {
return 1
}
func (self *SysStatus) Size() uint8 {
return 31
}
// The system time is the time of the master clock, typically the computer clock of the main onboard computer.
type SystemTime struct {
TimeUnixUsec uint64 // Timestamp of the master clock in microseconds since UNIX epoch.
TimeBootMs uint32 // Timestamp of the component clock since boot time in milliseconds.
}
func (self *SystemTime) ID() uint8 {
return 2
}
func (self *SystemTime) Size() uint8 {
return 12
}
// A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.
type Ping struct {
TimeUsec uint64 // Unix timestamp in microseconds
Seq uint32 // PING sequence
TargetSystem uint8 // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
TargetComponent uint8 // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
}
func (self *Ping) ID() uint8 {
return 4
}
func (self *Ping) Size() uint8 {
return 14
}
// Request to control this MAV
type ChangeOperatorControl struct {
TargetSystem uint8 // System the GCS requests control for
ControlRequest uint8 // 0: request control of this MAV, 1: Release control of this MAV
Version uint8 // 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
Passkey [25]byte // Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
}
func (self *ChangeOperatorControl) ID() uint8 {
return 5
}
func (self *ChangeOperatorControl) Size() uint8 {
return 28
}
// Accept / deny control of this MAV
type ChangeOperatorControlAck struct {
GcsSystemId uint8 // ID of the GCS this message
ControlRequest uint8 // 0: request control of this MAV, 1: Release control of this MAV
Ack uint8 // 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
}
func (self *ChangeOperatorControlAck) ID() uint8 {
return 6
}
func (self *ChangeOperatorControlAck) Size() uint8 {
return 3
}
// Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.
type AuthKey struct {
Key [32]byte // key
}
func (self *AuthKey) ID() uint8 {
return 7
}
func (self *AuthKey) Size() uint8 {
return 32
}
// Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.
type SetMode struct {
CustomMode uint32 // The new autopilot-specific mode. This field can be ignored by an autopilot.
TargetSystem uint8 // The system setting the mode
BaseMode uint8 // The new base mode
}
func (self *SetMode) ID() uint8 {
return 11
}
func (self *SetMode) Size() uint8 {
return 6
}
// Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.
type ParamRequestRead struct {
ParamIndex int16 // Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
TargetSystem uint8 // System ID
TargetComponent uint8 // Component ID
ParamId [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
}
func (self *ParamRequestRead) ID() uint8 {
return 20
}
func (self *ParamRequestRead) Size() uint8 {
return 20
}
// Request all parameters of this component. After his request, all parameters are emitted.
type ParamRequestList struct {
TargetSystem uint8 // System ID
TargetComponent uint8 // Component ID
}
func (self *ParamRequestList) ID() uint8 {
return 21
}
func (self *ParamRequestList) Size() uint8 {
return 2
}
// Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.
type ParamValue struct {
ParamValue float32 // Onboard parameter value
ParamCount uint16 // Total number of onboard parameters
ParamIndex uint16 // Index of this onboard parameter
ParamId [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
ParamType uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
}
func (self *ParamValue) ID() uint8 {
return 22
}
func (self *ParamValue) Size() uint8 {
return 25
}
// Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.
type ParamSet struct {
ParamValue float32 // Onboard parameter value
TargetSystem uint8 // System ID
TargetComponent uint8 // Component ID
ParamId [16]byte // Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
ParamType uint8 // Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
}
func (self *ParamSet) ID() uint8 {
return 23
}
func (self *ParamSet) Size() uint8 {
return 23
}
// The global position, as returned by the Global Positioning System (GPS). This is
// NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).
type GpsRawInt struct {
TimeUsec uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Lat int32 // Latitude (WGS84), in degrees * 1E7
Lon int32 // Longitude (WGS84), in degrees * 1E7
Alt int32 // Altitude (WGS84), in meters * 1000 (positive for up)
Eph uint16 // GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
Epv uint16 // GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
Vel uint16 // GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
Cog uint16 // Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
FixType uint8 // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
SatellitesVisible uint8 // Number of satellites visible. If unknown, set to 255
}
func (self *GpsRawInt) ID() uint8 {
return 24
}
func (self *GpsRawInt) Size() uint8 {
return 30
}
// The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.
type GpsStatus struct {
SatellitesVisible uint8 // Number of satellites visible
SatellitePrn [20]uint8 // Global satellite ID
SatelliteUsed [20]uint8 // 0: Satellite not used, 1: used for localization
SatelliteElevation [20]uint8 // Elevation (0: right on top of receiver, 90: on the horizon) of satellite
SatelliteAzimuth [20]uint8 // Direction of satellite, 0: 0 deg, 255: 360 deg.
SatelliteSnr [20]uint8 // Signal to noise ratio of satellite
}
func (self *GpsStatus) ID() uint8 {
return 25
}
func (self *GpsStatus) Size() uint8 {
return 101
}
// The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units
type ScaledImu struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
Xacc int16 // X acceleration (mg)
Yacc int16 // Y acceleration (mg)
Zacc int16 // Z acceleration (mg)
Xgyro int16 // Angular speed around X axis (millirad /sec)
Ygyro int16 // Angular speed around Y axis (millirad /sec)
Zgyro int16 // Angular speed around Z axis (millirad /sec)
Xmag int16 // X Magnetic field (milli tesla)
Ymag int16 // Y Magnetic field (milli tesla)
Zmag int16 // Z Magnetic field (milli tesla)
}
func (self *ScaledImu) ID() uint8 {
return 26
}
func (self *ScaledImu) Size() uint8 {
return 22
}
// The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.
type RawImu struct {
TimeUsec uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Xacc int16 // X acceleration (raw)
Yacc int16 // Y acceleration (raw)
Zacc int16 // Z acceleration (raw)
Xgyro int16 // Angular speed around X axis (raw)
Ygyro int16 // Angular speed around Y axis (raw)
Zgyro int16 // Angular speed around Z axis (raw)
Xmag int16 // X Magnetic field (raw)
Ymag int16 // Y Magnetic field (raw)
Zmag int16 // Z Magnetic field (raw)
}
func (self *RawImu) ID() uint8 {
return 27
}
func (self *RawImu) Size() uint8 {
return 26
}
// The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.
type RawPressure struct {
TimeUsec uint64 // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
PressAbs int16 // Absolute pressure (raw)
PressDiff1 int16 // Differential pressure 1 (raw)
PressDiff2 int16 // Differential pressure 2 (raw)
Temperature int16 // Raw Temperature measurement (raw)
}
func (self *RawPressure) ID() uint8 {
return 28
}
func (self *RawPressure) Size() uint8 {
return 16
}
// The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.
type ScaledPressure struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
PressAbs float32 // Absolute pressure (hectopascal)
PressDiff float32 // Differential pressure 1 (hectopascal)
Temperature int16 // Temperature measurement (0.01 degrees celsius)
}
func (self *ScaledPressure) ID() uint8 {
return 29
}
func (self *ScaledPressure) Size() uint8 {
return 14
}
// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).
type Attitude struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
Roll float32 // Roll angle (rad, -pi..+pi)
Pitch float32 // Pitch angle (rad, -pi..+pi)
Yaw float32 // Yaw angle (rad, -pi..+pi)
Rollspeed float32 // Roll angular speed (rad/s)
Pitchspeed float32 // Pitch angular speed (rad/s)
Yawspeed float32 // Yaw angular speed (rad/s)
}
func (self *Attitude) ID() uint8 {
return 30
}
func (self *Attitude) Size() uint8 {
return 28
}
// The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion.
type AttitudeQuaternion struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
Q1 float32 // Quaternion component 1
Q2 float32 // Quaternion component 2
Q3 float32 // Quaternion component 3
Q4 float32 // Quaternion component 4
Rollspeed float32 // Roll angular speed (rad/s)
Pitchspeed float32 // Pitch angular speed (rad/s)
Yawspeed float32 // Yaw angular speed (rad/s)
}
func (self *AttitudeQuaternion) ID() uint8 {
return 31
}
func (self *AttitudeQuaternion) Size() uint8 {
return 32
}
// The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
type LocalPositionNed struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
X float32 // X Position
Y float32 // Y Position
Z float32 // Z Position
Vx float32 // X Speed
Vy float32 // Y Speed
Vz float32 // Z Speed
}
func (self *LocalPositionNed) ID() uint8 {
return 32
}
func (self *LocalPositionNed) Size() uint8 {
return 28
}
// The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It
// is designed as scaled integer message since the resolution of float is not sufficient.
type GlobalPositionInt struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
Lat int32 // Latitude, expressed as * 1E7
Lon int32 // Longitude, expressed as * 1E7
Alt int32 // Altitude in meters, expressed as * 1000 (millimeters), above MSL
RelativeAlt int32 // Altitude above ground in meters, expressed as * 1000 (millimeters)
Vx int16 // Ground X Speed (Latitude), expressed as m/s * 100
Vy int16 // Ground Y Speed (Longitude), expressed as m/s * 100
Vz int16 // Ground Z Speed (Altitude), expressed as m/s * 100
Hdg uint16 // Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
}
func (self *GlobalPositionInt) ID() uint8 {
return 33
}
func (self *GlobalPositionInt) Size() uint8 {
return 28
}
// The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.
type RcChannelsScaled struct {
TimeBootMs uint32 // Timestamp (milliseconds since system boot)
Chan1Scaled int16 // RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan2Scaled int16 // RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan3Scaled int16 // RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan4Scaled int16 // RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan5Scaled int16 // RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan6Scaled int16 // RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan7Scaled int16 // RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
Chan8Scaled int16 // RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.