-
Notifications
You must be signed in to change notification settings - Fork 17
/
mavlink.py
4731 lines (4014 loc) · 256 KB
/
mavlink.py
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: ardupilotmega.xml,common.xml
Note: this file has been auto-generated. DO NOT EDIT
'''
import struct, array, mavutil, time
WIRE_PROTOCOL_VERSION = "0.9"
class MAVLink_header(object):
'''MAVLink message header'''
def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0):
self.mlen = mlen
self.seq = seq
self.srcSystem = srcSystem
self.srcComponent = srcComponent
self.msgId = msgId
def pack(self):
return struct.pack('BBBBBB', 85, self.mlen, self.seq,
self.srcSystem, self.srcComponent, self.msgId)
class MAVLink_message(object):
'''base MAVLink message class'''
def __init__(self, msgId, name):
self._header = MAVLink_header(msgId)
self._payload = None
self._msgbuf = None
self._crc = None
self._fieldnames = []
self._type = name
def get_msgbuf(self):
return self._msgbuf
def get_header(self):
return self._header
def get_payload(self):
return self._payload
def get_crc(self):
return self._crc
def get_fieldnames(self):
return self._fieldnames
def get_type(self):
return self._type
def get_msgId(self):
return self._header.msgId
def get_srcSystem(self):
return self._header.srcSystem
def get_srcComponent(self):
return self._header.srcComponent
def get_seq(self):
return self._header.seq
def __str__(self):
ret = '%s {' % self._type
for a in self._fieldnames:
v = getattr(self, a)
ret += '%s : %s, ' % (a, v)
ret = ret[0:-2] + '}'
return ret
def pack(self, mav, crc_extra, payload):
self._payload = payload
self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq,
mav.srcSystem, mav.srcComponent)
self._msgbuf = self._header.pack() + payload
crc = mavutil.x25crc(self._msgbuf[1:])
if False: # using CRC extra
crc.accumulate(chr(crc_extra))
self._crc = crc.crc
self._msgbuf += struct.pack('<H', self._crc)
return self._msgbuf
# enums
# MAV_MOUNT_MODE
MAV_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop
# stabilization
MAV_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.
MAV_MOUNT_MODE_MAVLINK_TARGETING = 2 # Load neutral position and start MAVLink Roll,Pitch,Yaw control with
# stabilization
MAV_MOUNT_MODE_RC_TARGETING = 3 # Load neutral position and start RC Roll,Pitch,Yaw control with
# stabilization
MAV_MOUNT_MODE_GPS_POINT = 4 # Load neutral position and start to point to Lat,Lon,Alt
MAV_MOUNT_MODE_ENUM_END = 5 #
# MAV_CMD
MAV_CMD_NAV_WAYPOINT = 16 # Navigate to waypoint.
MAV_CMD_NAV_LOITER_UNLIM = 17 # Loiter around this waypoint an unlimited amount of time
MAV_CMD_NAV_LOITER_TURNS = 18 # Loiter around this waypoint for X turns
MAV_CMD_NAV_LOITER_TIME = 19 # Loiter around this waypoint for X seconds
MAV_CMD_NAV_RETURN_TO_LAUNCH = 20 # Return to launch location
MAV_CMD_NAV_LAND = 21 # Land at location
MAV_CMD_NAV_TAKEOFF = 22 # Takeoff from ground / hand
MAV_CMD_NAV_ROI = 80 # 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_PATHPLANNING = 81 # Control autonomous path planning on the MAV.
MAV_CMD_NAV_LAST = 95 # NOP - This command is only used to mark the upper limit of the
# NAV/ACTION commands in the enumeration
MAV_CMD_CONDITION_DELAY = 112 # Delay mission state machine.
MAV_CMD_CONDITION_CHANGE_ALT = 113 # Ascend/descend at rate. Delay mission state machine until desired
# altitude reached.
MAV_CMD_CONDITION_DISTANCE = 114 # Delay mission state machine until within desired distance of next NAV
# point.
MAV_CMD_CONDITION_YAW = 115 # Reach a certain target angle.
MAV_CMD_CONDITION_LAST = 159 # NOP - This command is only used to mark the upper limit of the
# CONDITION commands in the enumeration
MAV_CMD_DO_SET_MODE = 176 # Set system mode.
MAV_CMD_DO_JUMP = 177 # Jump to the desired command in the mission list. Repeat this action
# only the specified number of times
MAV_CMD_DO_CHANGE_SPEED = 178 # Change speed and/or throttle set points.
MAV_CMD_DO_SET_HOME = 179 # Changes the home location either to the current location or a
# specified location.
MAV_CMD_DO_SET_PARAMETER = 180 # Set a system parameter. Caution! Use of this command requires
# knowledge of the numeric enumeration value
# of the parameter.
MAV_CMD_DO_SET_RELAY = 181 # Set a relay to a condition.
MAV_CMD_DO_REPEAT_RELAY = 182 # Cycle a relay on and off for a desired number of cyles with a desired
# period.
MAV_CMD_DO_SET_SERVO = 183 # Set a servo to a desired PWM value.
MAV_CMD_DO_REPEAT_SERVO = 184 # Cycle a between its nominal setting and a desired PWM for a desired
# number of cycles with a desired period.
MAV_CMD_DO_CONTROL_VIDEO = 200 # Control onboard camera capturing.
MAV_CMD_DO_SET_ROI = 201 # 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
# devices such as cameras.
MAV_CMD_DO_DIGICAM_CONFIGURE = 202 # Mission command to configure an on-board camera controller system.
MAV_CMD_DO_DIGICAM_CONTROL = 203 # Mission command to control an on-board camera controller system.
MAV_CMD_DO_MOUNT_CONFIGURE = 204 # Mission command to configure a camera or antenna mount
MAV_CMD_DO_MOUNT_CONTROL = 205 # Mission command to control a camera or antenna mount
MAV_CMD_DO_LAST = 240 # NOP - This command is only used to mark the upper limit of the DO
# commands in the enumeration
MAV_CMD_PREFLIGHT_CALIBRATION = 241 # Trigger calibration. This command will be only accepted if in pre-
# flight mode.
MAV_CMD_PREFLIGHT_STORAGE = 245 # Request storage of different parameter values and logs. This command
# will be only accepted if in pre-flight mode.
MAV_CMD_ENUM_END = 246 #
# FENCE_ACTION
FENCE_ACTION_NONE = 0 # Disable fenced mode
FENCE_ACTION_GUIDED = 1 # Switched to guided mode to return point (fence point 0)
FENCE_ACTION_ENUM_END = 2 #
# FENCE_BREACH
FENCE_BREACH_NONE = 0 # No last fence breach
FENCE_BREACH_MINALT = 1 # Breached minimum altitude
FENCE_BREACH_MAXALT = 2 # Breached minimum altitude
FENCE_BREACH_BOUNDARY = 3 # Breached fence boundary
FENCE_BREACH_ENUM_END = 4 #
# MAV_DATA_STREAM
MAV_DATA_STREAM_ALL = 0 # Enable all data streams
MAV_DATA_STREAM_RAW_SENSORS = 1 # Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.
MAV_DATA_STREAM_EXTENDED_STATUS = 2 # Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS
MAV_DATA_STREAM_RC_CHANNELS = 3 # Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW
MAV_DATA_STREAM_RAW_CONTROLLER = 4 # Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT,
# NAV_CONTROLLER_OUTPUT.
MAV_DATA_STREAM_POSITION = 6 # Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
MAV_DATA_STREAM_EXTRA1 = 10 # Dependent on the autopilot
MAV_DATA_STREAM_EXTRA2 = 11 # Dependent on the autopilot
MAV_DATA_STREAM_EXTRA3 = 12 # Dependent on the autopilot
MAV_DATA_STREAM_ENUM_END = 13 #
# MAV_ROI
MAV_ROI_NONE = 0 # No region of interest.
MAV_ROI_WPNEXT = 1 # Point toward next waypoint.
MAV_ROI_WPINDEX = 2 # Point toward given waypoint.
MAV_ROI_LOCATION = 3 # Point toward fixed location.
MAV_ROI_TARGET = 4 # Point toward of given id.
MAV_ROI_ENUM_END = 5 #
# message IDs
MAVLINK_MSG_ID_BAD_DATA = -1
MAVLINK_MSG_ID_SENSOR_OFFSETS = 150
MAVLINK_MSG_ID_SET_MAG_OFFSETS = 151
MAVLINK_MSG_ID_MEMINFO = 152
MAVLINK_MSG_ID_AP_ADC = 153
MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154
MAVLINK_MSG_ID_DIGICAM_CONTROL = 155
MAVLINK_MSG_ID_MOUNT_CONFIGURE = 156
MAVLINK_MSG_ID_MOUNT_CONTROL = 157
MAVLINK_MSG_ID_MOUNT_STATUS = 158
MAVLINK_MSG_ID_FENCE_POINT = 160
MAVLINK_MSG_ID_FENCE_FETCH_POINT = 161
MAVLINK_MSG_ID_FENCE_STATUS = 162
MAVLINK_MSG_ID_HEARTBEAT = 0
MAVLINK_MSG_ID_BOOT = 1
MAVLINK_MSG_ID_SYSTEM_TIME = 2
MAVLINK_MSG_ID_PING = 3
MAVLINK_MSG_ID_SYSTEM_TIME_UTC = 4
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL = 5
MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK = 6
MAVLINK_MSG_ID_AUTH_KEY = 7
MAVLINK_MSG_ID_ACTION_ACK = 9
MAVLINK_MSG_ID_ACTION = 10
MAVLINK_MSG_ID_SET_MODE = 11
MAVLINK_MSG_ID_SET_NAV_MODE = 12
MAVLINK_MSG_ID_PARAM_REQUEST_READ = 20
MAVLINK_MSG_ID_PARAM_REQUEST_LIST = 21
MAVLINK_MSG_ID_PARAM_VALUE = 22
MAVLINK_MSG_ID_PARAM_SET = 23
MAVLINK_MSG_ID_GPS_RAW_INT = 25
MAVLINK_MSG_ID_SCALED_IMU = 26
MAVLINK_MSG_ID_GPS_STATUS = 27
MAVLINK_MSG_ID_RAW_IMU = 28
MAVLINK_MSG_ID_RAW_PRESSURE = 29
MAVLINK_MSG_ID_SCALED_PRESSURE = 38
MAVLINK_MSG_ID_ATTITUDE = 30
MAVLINK_MSG_ID_LOCAL_POSITION = 31
MAVLINK_MSG_ID_GLOBAL_POSITION = 33
MAVLINK_MSG_ID_GPS_RAW = 32
MAVLINK_MSG_ID_SYS_STATUS = 34
MAVLINK_MSG_ID_RC_CHANNELS_RAW = 35
MAVLINK_MSG_ID_RC_CHANNELS_SCALED = 36
MAVLINK_MSG_ID_SERVO_OUTPUT_RAW = 37
MAVLINK_MSG_ID_WAYPOINT = 39
MAVLINK_MSG_ID_WAYPOINT_REQUEST = 40
MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT = 41
MAVLINK_MSG_ID_WAYPOINT_CURRENT = 42
MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST = 43
MAVLINK_MSG_ID_WAYPOINT_COUNT = 44
MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL = 45
MAVLINK_MSG_ID_WAYPOINT_REACHED = 46
MAVLINK_MSG_ID_WAYPOINT_ACK = 47
MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN = 48
MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET = 49
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET = 50
MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT = 51
MAVLINK_MSG_ID_CONTROL_STATUS = 52
MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA = 53
MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA = 54
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST = 55
MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST = 56
MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT = 57
MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT = 58
MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT = 62
MAVLINK_MSG_ID_POSITION_TARGET = 63
MAVLINK_MSG_ID_STATE_CORRECTION = 64
MAVLINK_MSG_ID_SET_ALTITUDE = 65
MAVLINK_MSG_ID_REQUEST_DATA_STREAM = 66
MAVLINK_MSG_ID_HIL_STATE = 67
MAVLINK_MSG_ID_HIL_CONTROLS = 68
MAVLINK_MSG_ID_MANUAL_CONTROL = 69
MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE = 70
MAVLINK_MSG_ID_GLOBAL_POSITION_INT = 73
MAVLINK_MSG_ID_VFR_HUD = 74
MAVLINK_MSG_ID_COMMAND = 75
MAVLINK_MSG_ID_COMMAND_ACK = 76
MAVLINK_MSG_ID_OPTICAL_FLOW = 100
MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT = 140
MAVLINK_MSG_ID_DEBUG_VECT = 251
MAVLINK_MSG_ID_NAMED_VALUE_FLOAT = 252
MAVLINK_MSG_ID_NAMED_VALUE_INT = 253
MAVLINK_MSG_ID_STATUSTEXT = 254
MAVLINK_MSG_ID_DEBUG = 255
class MAVLink_sensor_offsets_message(MAVLink_message):
'''
Offsets and calibrations values for hardware sensors.
This makes it easier to debug the calibration process.
'''
def __init__(self, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SENSOR_OFFSETS, 'SENSOR_OFFSETS')
self._fieldnames = ['mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z', 'mag_declination', 'raw_press', 'raw_temp', 'gyro_cal_x', 'gyro_cal_y', 'gyro_cal_z', 'accel_cal_x', 'accel_cal_y', 'accel_cal_z']
self.mag_ofs_x = mag_ofs_x
self.mag_ofs_y = mag_ofs_y
self.mag_ofs_z = mag_ofs_z
self.mag_declination = mag_declination
self.raw_press = raw_press
self.raw_temp = raw_temp
self.gyro_cal_x = gyro_cal_x
self.gyro_cal_y = gyro_cal_y
self.gyro_cal_z = gyro_cal_z
self.accel_cal_x = accel_cal_x
self.accel_cal_y = accel_cal_y
self.accel_cal_z = accel_cal_z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 143, struct.pack('>hhhfiiffffff', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.mag_declination, self.raw_press, self.raw_temp, self.gyro_cal_x, self.gyro_cal_y, self.gyro_cal_z, self.accel_cal_x, self.accel_cal_y, self.accel_cal_z))
class MAVLink_set_mag_offsets_message(MAVLink_message):
'''
set the magnetometer offsets
'''
def __init__(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MAG_OFFSETS, 'SET_MAG_OFFSETS')
self._fieldnames = ['target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z']
self.target_system = target_system
self.target_component = target_component
self.mag_ofs_x = mag_ofs_x
self.mag_ofs_y = mag_ofs_y
self.mag_ofs_z = mag_ofs_z
def pack(self, mav):
return MAVLink_message.pack(self, mav, 29, struct.pack('>BBhhh', self.target_system, self.target_component, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z))
class MAVLink_meminfo_message(MAVLink_message):
'''
state of APM memory
'''
def __init__(self, brkval, freemem):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMINFO, 'MEMINFO')
self._fieldnames = ['brkval', 'freemem']
self.brkval = brkval
self.freemem = freemem
def pack(self, mav):
return MAVLink_message.pack(self, mav, 208, struct.pack('>HH', self.brkval, self.freemem))
class MAVLink_ap_adc_message(MAVLink_message):
'''
raw ADC output
'''
def __init__(self, adc1, adc2, adc3, adc4, adc5, adc6):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_AP_ADC, 'AP_ADC')
self._fieldnames = ['adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6']
self.adc1 = adc1
self.adc2 = adc2
self.adc3 = adc3
self.adc4 = adc4
self.adc5 = adc5
self.adc6 = adc6
def pack(self, mav):
return MAVLink_message.pack(self, mav, 188, struct.pack('>HHHHHH', self.adc1, self.adc2, self.adc3, self.adc4, self.adc5, self.adc6))
class MAVLink_digicam_configure_message(MAVLink_message):
'''
Configure on-board Camera Control System.
'''
def __init__(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, 'DIGICAM_CONFIGURE')
self._fieldnames = ['target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value']
self.target_system = target_system
self.target_component = target_component
self.mode = mode
self.shutter_speed = shutter_speed
self.aperture = aperture
self.iso = iso
self.exposure_type = exposure_type
self.command_id = command_id
self.engine_cut_off = engine_cut_off
self.extra_param = extra_param
self.extra_value = extra_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 118, struct.pack('>BBBHBBBBBBf', self.target_system, self.target_component, self.mode, self.shutter_speed, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param, self.extra_value))
class MAVLink_digicam_control_message(MAVLink_message):
'''
Control on-board Camera Control System to take shots.
'''
def __init__(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONTROL, 'DIGICAM_CONTROL')
self._fieldnames = ['target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value']
self.target_system = target_system
self.target_component = target_component
self.session = session
self.zoom_pos = zoom_pos
self.zoom_step = zoom_step
self.focus_lock = focus_lock
self.shot = shot
self.command_id = command_id
self.extra_param = extra_param
self.extra_value = extra_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 242, struct.pack('>BBBBbBBBBf', self.target_system, self.target_component, self.session, self.zoom_pos, self.zoom_step, self.focus_lock, self.shot, self.command_id, self.extra_param, self.extra_value))
class MAVLink_mount_configure_message(MAVLink_message):
'''
Message to configure a camera mount, directional antenna, etc.
'''
def __init__(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONFIGURE, 'MOUNT_CONFIGURE')
self._fieldnames = ['target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw']
self.target_system = target_system
self.target_component = target_component
self.mount_mode = mount_mode
self.stab_roll = stab_roll
self.stab_pitch = stab_pitch
self.stab_yaw = stab_yaw
def pack(self, mav):
return MAVLink_message.pack(self, mav, 19, struct.pack('>BBBBBB', self.target_system, self.target_component, self.mount_mode, self.stab_roll, self.stab_pitch, self.stab_yaw))
class MAVLink_mount_control_message(MAVLink_message):
'''
Message to control a camera mount, directional antenna, etc.
'''
def __init__(self, target_system, target_component, input_a, input_b, input_c, save_position):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONTROL, 'MOUNT_CONTROL')
self._fieldnames = ['target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position']
self.target_system = target_system
self.target_component = target_component
self.input_a = input_a
self.input_b = input_b
self.input_c = input_c
self.save_position = save_position
def pack(self, mav):
return MAVLink_message.pack(self, mav, 97, struct.pack('>BBiiiB', self.target_system, self.target_component, self.input_a, self.input_b, self.input_c, self.save_position))
class MAVLink_mount_status_message(MAVLink_message):
'''
Message with some status from APM to GCS about camera or
antenna mount
'''
def __init__(self, target_system, target_component, pointing_a, pointing_b, pointing_c):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_STATUS, 'MOUNT_STATUS')
self._fieldnames = ['target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c']
self.target_system = target_system
self.target_component = target_component
self.pointing_a = pointing_a
self.pointing_b = pointing_b
self.pointing_c = pointing_c
def pack(self, mav):
return MAVLink_message.pack(self, mav, 233, struct.pack('>BBiii', self.target_system, self.target_component, self.pointing_a, self.pointing_b, self.pointing_c))
class MAVLink_fence_point_message(MAVLink_message):
'''
A fence point. Used to set a point when from GCS
-> MAV. Also used to return a point from MAV -> GCS
'''
def __init__(self, target_system, target_component, idx, count, lat, lng):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT')
self._fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng']
self.target_system = target_system
self.target_component = target_component
self.idx = idx
self.count = count
self.lat = lat
self.lng = lng
def pack(self, mav):
return MAVLink_message.pack(self, mav, 18, struct.pack('>BBBBff', self.target_system, self.target_component, self.idx, self.count, self.lat, self.lng))
class MAVLink_fence_fetch_point_message(MAVLink_message):
'''
Request a current fence point from MAV
'''
def __init__(self, target_system, target_component, idx):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_FETCH_POINT, 'FENCE_FETCH_POINT')
self._fieldnames = ['target_system', 'target_component', 'idx']
self.target_system = target_system
self.target_component = target_component
self.idx = idx
def pack(self, mav):
return MAVLink_message.pack(self, mav, 68, struct.pack('>BBB', self.target_system, self.target_component, self.idx))
class MAVLink_fence_status_message(MAVLink_message):
'''
Status of geo-fencing. Sent in extended status
stream when fencing enabled
'''
def __init__(self, breach_status, breach_count, breach_type, breach_time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_STATUS, 'FENCE_STATUS')
self._fieldnames = ['breach_status', 'breach_count', 'breach_type', 'breach_time']
self.breach_status = breach_status
self.breach_count = breach_count
self.breach_type = breach_type
self.breach_time = breach_time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 136, struct.pack('>BHBI', self.breach_status, self.breach_count, self.breach_type, self.breach_time))
class MAVLink_heartbeat_message(MAVLink_message):
'''
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).
'''
def __init__(self, type, autopilot, mavlink_version):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT')
self._fieldnames = ['type', 'autopilot', 'mavlink_version']
self.type = type
self.autopilot = autopilot
self.mavlink_version = mavlink_version
def pack(self, mav):
return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version))
class MAVLink_boot_message(MAVLink_message):
'''
The boot message indicates that a system is starting. The
onboard software version allows to keep track of onboard
soft/firmware revisions.
'''
def __init__(self, version):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_BOOT, 'BOOT')
self._fieldnames = ['version']
self.version = version
def pack(self, mav):
return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version))
class MAVLink_system_time_message(MAVLink_message):
'''
The system time is the time of the master clock, typically the
computer clock of the main onboard computer.
'''
def __init__(self, time_usec):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME')
self._fieldnames = ['time_usec']
self.time_usec = time_usec
def pack(self, mav):
return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec))
class MAVLink_ping_message(MAVLink_message):
'''
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.
'''
def __init__(self, seq, target_system, target_component, time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING')
self._fieldnames = ['seq', 'target_system', 'target_component', 'time']
self.seq = seq
self.target_system = target_system
self.target_component = target_component
self.time = time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time))
class MAVLink_system_time_utc_message(MAVLink_message):
'''
UTC date and time from GPS module
'''
def __init__(self, utc_date, utc_time):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, 'SYSTEM_TIME_UTC')
self._fieldnames = ['utc_date', 'utc_time']
self.utc_date = utc_date
self.utc_time = utc_time
def pack(self, mav):
return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time))
class MAVLink_change_operator_control_message(MAVLink_message):
'''
Request to control this MAV
'''
def __init__(self, target_system, control_request, version, passkey):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, 'CHANGE_OPERATOR_CONTROL')
self._fieldnames = ['target_system', 'control_request', 'version', 'passkey']
self.target_system = target_system
self.control_request = control_request
self.version = version
self.passkey = passkey
def pack(self, mav):
return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey))
class MAVLink_change_operator_control_ack_message(MAVLink_message):
'''
Accept / deny control of this MAV
'''
def __init__(self, gcs_system_id, control_request, ack):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, 'CHANGE_OPERATOR_CONTROL_ACK')
self._fieldnames = ['gcs_system_id', 'control_request', 'ack']
self.gcs_system_id = gcs_system_id
self.control_request = control_request
self.ack = ack
def pack(self, mav):
return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack))
class MAVLink_auth_key_message(MAVLink_message):
'''
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.
'''
def __init__(self, key):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_AUTH_KEY, 'AUTH_KEY')
self._fieldnames = ['key']
self.key = key
def pack(self, mav):
return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key))
class MAVLink_action_ack_message(MAVLink_message):
'''
This message acknowledges an action. IMPORTANT: The
acknowledgement can be also negative, e.g. the MAV rejects a
reset message because it is in-flight. The action ids are
defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h
'''
def __init__(self, action, result):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION_ACK, 'ACTION_ACK')
self._fieldnames = ['action', 'result']
self.action = action
self.result = result
def pack(self, mav):
return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result))
class MAVLink_action_message(MAVLink_message):
'''
An action message allows to execute a certain onboard action.
These include liftoff, land, storing parameters too EEPROM,
shutddown, etc. The action ids are defined in ENUM MAV_ACTION
in mavlink/include/mavlink_types.h
'''
def __init__(self, target, target_component, action):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION, 'ACTION')
self._fieldnames = ['target', 'target_component', 'action']
self.target = target
self.target_component = target_component
self.action = action
def pack(self, mav):
return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action))
class MAVLink_set_mode_message(MAVLink_message):
'''
Set the system mode, as defined by enum MAV_MODE in
mavlink/include/mavlink_types.h. There is no target component
id as the mode is by definition for the overall aircraft, not
only for one component.
'''
def __init__(self, target, mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE')
self._fieldnames = ['target', 'mode']
self.target = target
self.mode = mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode))
class MAVLink_set_nav_mode_message(MAVLink_message):
'''
Set the system navigation mode, as defined by enum
MAV_NAV_MODE in mavlink/include/mavlink_types.h. The
navigation mode applies to the whole aircraft and thus all
components.
'''
def __init__(self, target, nav_mode):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_NAV_MODE, 'SET_NAV_MODE')
self._fieldnames = ['target', 'nav_mode']
self.target = target
self.nav_mode = nav_mode
def pack(self, mav):
return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode))
class MAVLink_param_request_read_message(MAVLink_message):
'''
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.
'''
def __init__(self, target_system, target_component, param_id, param_index):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ')
self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index']
self.target_system = target_system
self.target_component = target_component
self.param_id = param_id
self.param_index = param_index
def pack(self, mav):
return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15sh', self.target_system, self.target_component, self.param_id, self.param_index))
class MAVLink_param_request_list_message(MAVLink_message):
'''
Request all parameters of this component. After his request,
all parameters are emitted.
'''
def __init__(self, target_system, target_component):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 'PARAM_REQUEST_LIST')
self._fieldnames = ['target_system', 'target_component']
self.target_system = target_system
self.target_component = target_component
def pack(self, mav):
return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component))
class MAVLink_param_value_message(MAVLink_message):
'''
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.
'''
def __init__(self, param_id, param_value, param_count, param_index):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE')
self._fieldnames = ['param_id', 'param_value', 'param_count', 'param_index']
self.param_id = param_id
self.param_value = param_value
self.param_count = param_count
self.param_index = param_index
def pack(self, mav):
return MAVLink_message.pack(self, mav, 162, struct.pack('>15sfHH', self.param_id, self.param_value, self.param_count, self.param_index))
class MAVLink_param_set_message(MAVLink_message):
'''
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.
'''
def __init__(self, target_system, target_component, param_id, param_value):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET')
self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value']
self.target_system = target_system
self.target_component = target_component
self.param_id = param_id
self.param_value = param_value
def pack(self, mav):
return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15sf', self.target_system, self.target_component, self.param_id, self.param_value))
class MAVLink_gps_raw_int_message(MAVLink_message):
'''
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)
'''
def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT')
self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg']
self.usec = usec
self.fix_type = fix_type
self.lat = lat
self.lon = lon
self.alt = alt
self.eph = eph
self.epv = epv
self.v = v
self.hdg = hdg
def pack(self, mav):
return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg))
class MAVLink_scaled_imu_message(MAVLink_message):
'''
The RAW IMU readings for the usual 9DOF sensor setup. This
message should contain the scaled values to the described
units
'''
def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU')
self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
self.usec = usec
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
self.xgyro = xgyro
self.ygyro = ygyro
self.zgyro = zgyro
self.xmag = xmag
self.ymag = ymag
self.zmag = zmag
def pack(self, mav):
return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
class MAVLink_gps_status_message(MAVLink_message):
'''
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.
'''
def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_STATUS, 'GPS_STATUS')
self._fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr']
self.satellites_visible = satellites_visible
self.satellite_prn = satellite_prn
self.satellite_used = satellite_used
self.satellite_elevation = satellite_elevation
self.satellite_azimuth = satellite_azimuth
self.satellite_snr = satellite_snr
def pack(self, mav):
return MAVLink_message.pack(self, mav, 110, struct.pack('>B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr))
class MAVLink_raw_imu_message(MAVLink_message):
'''
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.
'''
def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU')
self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag']
self.usec = usec
self.xacc = xacc
self.yacc = yacc
self.zacc = zacc
self.xgyro = xgyro
self.ygyro = ygyro
self.zgyro = zgyro
self.xmag = xmag
self.ymag = ymag
self.zmag = zmag
def pack(self, mav):
return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag))
class MAVLink_raw_pressure_message(MAVLink_message):
'''
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.
'''
def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE')
self._fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature']
self.usec = usec
self.press_abs = press_abs
self.press_diff1 = press_diff1
self.press_diff2 = press_diff2
self.temperature = temperature
def pack(self, mav):
return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature))
class MAVLink_scaled_pressure_message(MAVLink_message):
'''
The pressure readings for the typical setup of one absolute
and differential pressure sensor. The units are as specified
in each field.
'''
def __init__(self, usec, press_abs, press_diff, temperature):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE')
self._fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature']
self.usec = usec
self.press_abs = press_abs
self.press_diff = press_diff
self.temperature = temperature
def pack(self, mav):
return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature))
class MAVLink_attitude_message(MAVLink_message):
'''
The attitude in the aeronautical frame (right-handed, Z-down,
X-front, Y-right).
'''
def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE')
self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed']
self.usec = usec
self.roll = roll
self.pitch = pitch
self.yaw = yaw
self.rollspeed = rollspeed
self.pitchspeed = pitchspeed
self.yawspeed = yawspeed
def pack(self, mav):
return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed))
class MAVLink_local_position_message(MAVLink_message):
'''
The filtered local position (e.g. fused computer vision and
accelerometers). Coordinate frame is right-handed, Z-axis down
(aeronautical frame)
'''
def __init__(self, usec, x, y, z, vx, vy, vz):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION, 'LOCAL_POSITION')
self._fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz']
self.usec = usec
self.x = x
self.y = y
self.z = z
self.vx = vx
self.vy = vy
self.vz = vz
def pack(self, mav):
return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz))
class MAVLink_global_position_message(MAVLink_message):
'''
The filtered global position (e.g. fused GPS and
accelerometers). Coordinate frame is right-handed, Z-axis up
(GPS frame)
'''
def __init__(self, usec, lat, lon, alt, vx, vy, vz):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION, 'GLOBAL_POSITION')
self._fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz']
self.usec = usec
self.lat = lat
self.lon = lon
self.alt = alt
self.vx = vx
self.vy = vy
self.vz = vz
def pack(self, mav):
return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz))
class MAVLink_gps_raw_message(MAVLink_message):
'''
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)
'''
def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW, 'GPS_RAW')
self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg']
self.usec = usec
self.fix_type = fix_type
self.lat = lat
self.lon = lon
self.alt = alt
self.eph = eph
self.epv = epv
self.v = v
self.hdg = hdg
def pack(self, mav):
return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg))
class MAVLink_sys_status_message(MAVLink_message):
'''
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.
'''
def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop):
MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS')
self._fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop']
self.mode = mode
self.nav_mode = nav_mode
self.status = status
self.load = load
self.vbat = vbat
self.battery_remaining = battery_remaining
self.packet_drop = packet_drop
def pack(self, mav):
return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop))
class MAVLink_rc_channels_raw_message(MAVLink_message):
'''
The RAW values of the RC channels received. The standard PPM
modulation is as follows: 1000 microseconds: 0%, 2000
microseconds: 100%. Individual receivers/transmitters might
violate this specification.
'''
def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi):