forked from ArduPilot/pymavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
mavutil.py
2582 lines (2289 loc) · 97.2 KB
/
mavutil.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
#!/usr/bin/env python
'''
mavlink python utility functions
Copyright Andrew Tridgell 2011-2019
Released under GNU LGPL version 3 or later
'''
from __future__ import print_function
from builtins import object
import socket, math, struct, time, os, fnmatch, array, sys, errno
import select
import copy
import json
import re
import platform
from pymavlink import mavexpression
# We want to re-export x25crc here
from pymavlink.generator.mavcrc import x25crc as x25crc
is_py3 = sys.version_info >= (3,0)
supports_type_annotations = sys.version_info >= (3,6)
# adding these extra imports allows pymavlink to be used directly with pyinstaller
# without having complex spec files. To allow for installs that don't have ardupilotmega
# at all we avoid throwing an exception if it isn't installed
try:
if supports_type_annotations:
from pymavlink.dialects.v10 import ardupilotmega
else:
from pymavlink.dialects.v10.python2 import ardupilotmega
except Exception:
pass
# maximum packet length for a single receive call - use the UDP limit
UDP_MAX_PACKET_LEN = 65535
# Store the MAVLink library for the currently-selected dialect
# (set by set_dialect())
mavlink = None
# Store the mavlink file currently being operated on
# (set by mavlink_connection())
mavfile_global = None
# If the caller hasn't specified a particular native/legacy version, use this
default_native = False
# link_id used for signing
global_link_id = 0
# Use a globally-set MAVLink dialect if one has been specified as an environment variable.
if not 'MAVLINK_DIALECT' in os.environ:
os.environ['MAVLINK_DIALECT'] = 'ardupilotmega'
def mavlink10():
'''return True if using MAVLink 1.0 or later'''
return not 'MAVLINK09' in os.environ
def mavlink20():
'''return True if using MAVLink 2.0'''
return 'MAVLINK20' in os.environ
def evaluate_expression(expression, vars, nocondition=False):
'''evaluation an expression'''
return mavexpression.evaluate_expression(expression, vars, nocondition)
def evaluate_condition(condition, vars):
'''evaluation a conditional (boolean) statement'''
if condition is None:
return True
v = evaluate_expression(condition, vars)
if v is None:
return False
return v
def u_ord(c):
if is_py3:
return c
return ord(c)
class location(object):
'''represent a GPS coordinate'''
def __init__(self, lat, lng, alt=0, heading=0):
self.lat = lat # in degrees
self.lng = lng # in degrees
self.alt = alt # in metres
self.heading = heading
def __str__(self):
return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)
def add_message(messages, mtype, msg):
'''add a msg to array of messages, taking account of instance messages'''
if msg._instance_field is None or getattr(msg, msg._instance_field, None) is None:
# simple case, no instance field
messages[mtype] = msg
return
instance_value = getattr(msg, msg._instance_field)
if not mtype in messages:
messages[mtype] = copy.copy(msg)
messages[mtype]._instances = {}
messages[mtype]._instances[instance_value] = msg
messages["%s[%s]" % (mtype, str(instance_value))] = copy.copy(msg)
return
messages[mtype]._instances[instance_value] = msg
prev_instances = messages[mtype]._instances
messages[mtype] = copy.copy(msg)
messages[mtype]._instances = prev_instances
messages["%s[%s]" % (mtype, str(instance_value))] = copy.copy(msg)
def set_dialect(dialect, with_type_annotations=None):
'''set the MAVLink dialect to work with.
For example, set_dialect("ardupilotmega")
'''
global mavlink, current_dialect
from .generator import mavparse
if with_type_annotations is None:
with_type_annotations = supports_type_annotations
legacy_python_module = "python2." if not with_type_annotations else ""
if 'MAVLINK20' in os.environ:
wire_protocol = mavparse.PROTOCOL_2_0
modname = "pymavlink.dialects.v20." + legacy_python_module + dialect
elif mavlink is None or mavlink.WIRE_PROTOCOL_VERSION == "1.0" or not 'MAVLINK09' in os.environ:
wire_protocol = mavparse.PROTOCOL_1_0
modname = "pymavlink.dialects.v10." + legacy_python_module + dialect
else:
wire_protocol = mavparse.PROTOCOL_0_9
modname = "pymavlink.dialects.v09." + legacy_python_module + dialect
try:
mod = __import__(modname)
except Exception:
# auto-generate the dialect module
from .generator.mavgen import mavgen_python_dialect
mavgen_python_dialect(dialect, wire_protocol, with_type_annotations=with_type_annotations)
mod = __import__(modname)
components = modname.split('.')
for comp in components[1:]:
mod = getattr(mod, comp)
current_dialect = dialect
mavlink = mod
# Set the default dialect. This is done here as it needs to be after the function declaration
set_dialect(os.environ['MAVLINK_DIALECT'])
class mavfile_state(object):
'''state for a particular system id'''
def __init__(self):
self.messages = { 'MAV' : self }
self.flightmode = "UNKNOWN"
self.vehicle_type = "UNKNOWN"
self.mav_type = mavlink.MAV_TYPE_FIXED_WING
self.mav_autopilot = mavlink.MAV_AUTOPILOT_GENERIC
self.base_mode = 0
self.armed = False # canonical arm state for the vehicle as a whole
if float(mavlink.WIRE_PROTOCOL_VERSION) >= 1:
self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0)
mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message
else:
self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0)
class param_state(object):
'''state for a particular system id/component id pair'''
def __init__(self):
self.params = {}
class mavfile(object):
'''a generic mavlink port'''
def __init__(self, fd, address, source_system=255, source_component=0, notimestamps=False, input=True, use_native=default_native):
global mavfile_global
if input:
mavfile_global = self
self.fd = fd
self.sysid = 0
self.param_sysid = (0,0)
self.address = address
self.timestamp = 0
self.last_seq = {}
self.mav_loss = 0
self.mav_count = 0
self.param_fetch_start = 0
# state for each sysid
self.sysid_state = {}
self.sysid_state[self.sysid] = mavfile_state()
# param state for each sysid/compid tuple
self.param_state = {}
self.param_state[self.param_sysid] = param_state()
# status of param fetch, indexed by sysid,compid tuple
self.source_system = source_system
self.source_component = source_component
self.first_byte = True
self.robust_parsing = True
self.mav = mavlink.MAVLink(self, srcSystem=self.source_system, srcComponent=self.source_component, use_native=use_native)
self.mav.robust_parsing = self.robust_parsing
self.logfile = None
self.logfile_raw = None
self.start_time = time.time()
self.message_hooks = []
self.idle_hooks = []
self.uptime = 0.0
self.notimestamps = notimestamps
self._timestamp = None
self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
self.stop_on_EOF = False
self.portdead = False
@property
def target_system(self):
return self.sysid
@property
def target_component(self):
return self.param_sysid[1]
@target_system.setter
def target_system(self, value):
self.sysid = value
if not self.sysid in self.sysid_state:
self.sysid_state[self.sysid] = mavfile_state()
if self.sysid != self.param_sysid[0]:
self.param_sysid = (self.sysid, self.param_sysid[1])
if not self.param_sysid in self.param_state:
self.param_state[self.param_sysid] = param_state()
@target_component.setter
def target_component(self, value):
if value != self.param_sysid[1]:
self.param_sysid = (self.param_sysid[0], value)
if not self.param_sysid in self.param_state:
self.param_state[self.param_sysid] = param_state()
@property
def params(self):
if self.param_sysid[1] == 0:
eff_tuple = (self.sysid, 1)
if eff_tuple in self.param_state:
return getattr(self.param_state[eff_tuple],'params')
return getattr(self.param_state[self.param_sysid],'params')
@property
def messages(self):
return getattr(self.sysid_state[self.sysid],'messages')
@property
def flightmode(self):
return getattr(self.sysid_state[self.sysid],'flightmode')
@flightmode.setter
def flightmode(self, value):
setattr(self.sysid_state[self.sysid],'flightmode',value)
@property
def vehicle_type(self):
return getattr(self.sysid_state[self.sysid],'vehicle_type')
@vehicle_type.setter
def vehicle_type(self, value):
setattr(self.sysid_state[self.sysid],'vehicle_type',value)
@property
def mav_type(self):
return getattr(self.sysid_state[self.sysid],'mav_type')
@mav_type.setter
def mav_type(self, value):
setattr(self.sysid_state[self.sysid],'mav_type',value)
@property
def base_mode(self):
return getattr(self.sysid_state[self.sysid],'base_mode')
@base_mode.setter
def base_mode(self, value):
setattr(self.sysid_state[self.sysid],'base_mode',value)
def auto_mavlink_version(self, buf):
'''auto-switch mavlink protocol version'''
global mavlink
if len(buf) == 0:
return
try:
magic = ord(buf[0])
except:
magic = buf[0]
if not magic in [ 85, 254, 253 ]:
return
self.first_byte = False
if self.WIRE_PROTOCOL_VERSION == "0.9" and magic == 254:
self.WIRE_PROTOCOL_VERSION = "1.0"
set_dialect(current_dialect)
elif self.WIRE_PROTOCOL_VERSION == "1.0" and magic == 85:
self.WIRE_PROTOCOL_VERSION = "0.9"
os.environ['MAVLINK09'] = '1'
set_dialect(current_dialect)
elif self.WIRE_PROTOCOL_VERSION != "2.0" and magic == 253:
self.WIRE_PROTOCOL_VERSION = "2.0"
os.environ['MAVLINK20'] = '1'
set_dialect(current_dialect)
else:
return
# switch protocol
(callback, callback_args, callback_kwargs) = (self.mav.callback,
self.mav.callback_args,
self.mav.callback_kwargs)
self.mav = mavlink.MAVLink(self, srcSystem=self.source_system, srcComponent=self.source_component)
self.mav.robust_parsing = self.robust_parsing
self.WIRE_PROTOCOL_VERSION = mavlink.WIRE_PROTOCOL_VERSION
(self.mav.callback, self.mav.callback_args, self.mav.callback_kwargs) = (callback,
callback_args,
callback_kwargs)
def recv(self, n=None):
'''default recv method'''
raise RuntimeError('no recv() method supplied')
def close(self, n=None):
'''default close method'''
raise RuntimeError('no close() method supplied')
def write(self, buf):
'''default write method'''
raise RuntimeError('no write() method supplied')
def select(self, timeout):
'''wait for up to timeout seconds for more data'''
if self.fd is None:
time.sleep(min(timeout,0.5))
return True
try:
(rin, win, xin) = select.select([self.fd], [], [], timeout)
except select.error:
return False
return len(rin) == 1
def pre_message(self):
'''default pre message call'''
return
def set_rtscts(self, enable):
'''enable/disable RTS/CTS if applicable'''
return
def probably_vehicle_heartbeat(self, msg):
if msg.get_srcComponent() == mavlink.MAV_COMP_ID_GIMBAL:
return False
if msg.type in (mavlink.MAV_TYPE_GCS,
mavlink.MAV_TYPE_GIMBAL,
mavlink.MAV_TYPE_ADSB,
mavlink.MAV_TYPE_ONBOARD_CONTROLLER):
return False
if msg.autopilot in frozenset([
mavlink.MAV_AUTOPILOT_INVALID
]):
return False
return True
def post_message(self, msg):
'''default post message call'''
if '_posted' in msg.__dict__:
return
msg._posted = True
msg._timestamp = time.time()
type = msg.get_type()
if 'usec' in msg.__dict__:
self.uptime = msg.usec * 1.0e-6
if 'time_boot_ms' in msg.__dict__:
self.uptime = msg.time_boot_ms * 1.0e-3
if self._timestamp is not None:
if self.notimestamps:
msg._timestamp = self.uptime
else:
msg._timestamp = self._timestamp
src_system = msg.get_srcSystem()
src_component = msg.get_srcComponent()
src_tuple = (src_system, src_component)
radio_tuple = (ord('3'), ord('D'))
if not src_system in self.sysid_state:
# we've seen a new system
self.sysid_state[src_system] = mavfile_state()
add_message(self.sysid_state[src_system].messages, type, msg)
if src_tuple == radio_tuple:
# as a special case radio msgs are added for all sysids
for s in self.sysid_state.keys():
self.sysid_state[s].messages[type] = msg
if not (src_tuple == radio_tuple or msg.get_msgId() < 0):
# Don't use unknown messages to calculate number of lost packets
if not src_tuple in self.last_seq:
last_seq = -1
else:
last_seq = self.last_seq[src_tuple]
seq = (last_seq+1) % 256
seq2 = msg.get_seq()
if seq != seq2 and last_seq != -1:
diff = (seq2 - seq) % 256
self.mav_loss += diff
#print("lost %u seq=%u seq2=%u last_seq=%u src_tupe=%s %s" % (diff, seq, seq2, last_seq, str(src_tuple), msg.get_type()))
self.last_seq[src_tuple] = seq2
self.mav_count += 1
self.timestamp = msg._timestamp
if type == 'HEARTBEAT' and self.probably_vehicle_heartbeat(msg):
if self.sysid == 0:
# lock onto id tuple of first vehicle heartbeat
self.sysid = src_system
if float(mavlink.WIRE_PROTOCOL_VERSION) >= 1:
self.flightmode = mode_string_v10(msg)
self.mav_type = msg.type
self.base_mode = msg.base_mode
self.sysid_state[self.sysid].armed = (msg.base_mode & mavlink.MAV_MODE_FLAG_SAFETY_ARMED)
self.sysid_state[self.sysid].mav_type = msg.type
self.sysid_state[self.sysid].mav_autopilot = msg.autopilot
elif type == 'HIGH_LATENCY2':
if self.sysid == 0:
# lock onto id tuple of first vehicle heartbeat
self.sysid = src_system
self.flightmode = mode_string_v10(msg)
self.mav_type = msg.type
if msg.autopilot == mavlink.MAV_AUTOPILOT_ARDUPILOTMEGA:
self.base_mode = msg.custom0
self.sysid_state[self.sysid].armed = (msg.custom0 & mavlink.MAV_MODE_FLAG_SAFETY_ARMED)
self.sysid_state[self.sysid].mav_type = msg.type
self.sysid_state[self.sysid].mav_autopilot = msg.autopilot
elif type == 'PARAM_VALUE':
if not src_tuple in self.param_state:
self.param_state[src_tuple] = param_state()
self.param_state[src_tuple].params[msg.param_id] = msg.param_value
elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9':
self.flightmode = mode_string_v09(msg)
elif type == 'GPS_RAW':
if self.sysid_state[src_system].messages['HOME'].fix_type < 2:
self.sysid_state[src_system].messages['HOME'] = msg
elif type == 'GPS_RAW_INT':
if self.sysid_state[src_system].messages['HOME'].fix_type < 3:
self.sysid_state[src_system].messages['HOME'] = msg
for hook in self.message_hooks:
hook(self, msg)
if (msg.get_signed() and
self.mav.signing.link_id == 0 and
msg.get_link_id() != 0 and
self.target_system == msg.get_srcSystem() and
self.target_component == msg.get_srcComponent()):
# change to link_id from incoming packet
self.mav.signing.link_id = msg.get_link_id()
def packet_loss(self):
'''packet loss as a percentage'''
if self.mav_count == 0:
return 0
return (100.0*self.mav_loss)/(self.mav_count+self.mav_loss)
def recv_msg(self):
'''message receive routine'''
self.pre_message()
while True:
n = self.mav.bytes_needed()
s = self.recv(n)
numnew = len(s)
if numnew != 0:
if self.logfile_raw:
if is_py3:
self.logfile_raw.write(s)
else:
self.logfile_raw.write(str(s))
if self.first_byte:
self.auto_mavlink_version(s)
# We always call parse_char even if the new string is empty, because the existing message buf might already have some valid packet
# we can extract
msg = self.mav.parse_char(s)
if msg:
if self.logfile and msg.get_type() != 'BAD_DATA' :
usec = int(time.time() * 1.0e6) & ~3
if is_py3:
self.logfile.write(struct.pack('>Q', usec) + msg.get_msgbuf())
else:
self.logfile.write(str(struct.pack('>Q', usec) + msg.get_msgbuf()))
self.post_message(msg)
return msg
else:
# if we failed to parse any messages _and_ no new bytes arrived, return immediately so the client has the option to
# timeout
if numnew == 0:
return None
def recv_match(self, condition=None, type=None, blocking=False, timeout=None):
'''recv the next MAVLink message that matches the given condition
type can be a string or a list of strings'''
if type is not None and not isinstance(type, list) and not isinstance(type, set):
type = [type]
start_time = time.time()
while True:
if timeout is not None:
now = time.time()
if now < start_time:
start_time = now # If an external process rolls back system time, we should not spin forever.
if start_time + timeout < time.time():
return None
m = self.recv_msg()
if m is None:
if blocking:
for hook in self.idle_hooks:
hook(self)
if timeout is None:
self.select(0.05)
else:
self.select(timeout/2)
continue
return None
if type is not None and not m.get_type() in type:
continue
if not evaluate_condition(condition, self.messages):
continue
return m
def check_condition(self, condition):
'''check if a condition is true'''
return evaluate_condition(condition, self.messages)
def mavlink10(self):
'''return True if using MAVLink 1.0 or later'''
return float(self.WIRE_PROTOCOL_VERSION) >= 1
def mavlink20(self):
'''return True if using MAVLink 2.0 or later'''
return float(self.WIRE_PROTOCOL_VERSION) >= 2
def setup_logfile(self, logfile, mode='wb'):
'''start logging to the given logfile, with timestamps'''
self.logfile = open(logfile, mode=mode)
def setup_logfile_raw(self, logfile, mode='wb'):
'''start logging raw bytes to the given logfile, without timestamps'''
self.logfile_raw = open(logfile, mode=mode)
def wait_heartbeat(self, blocking=True, timeout=None):
'''wait for a heartbeat so we know the target system IDs'''
return self.recv_match(type='HEARTBEAT', blocking=blocking, timeout=timeout)
def param_fetch_all(self):
'''initiate fetch of all parameters'''
if time.time() - self.param_fetch_start < 2.0:
# don't fetch too often
return
self.param_fetch_start = time.time()
self.mav.param_request_list_send(self.target_system, self.target_component)
def param_fetch_one(self, name):
'''initiate fetch of one parameter'''
try:
idx = int(name)
self.mav.param_request_read_send(self.target_system, self.target_component, b"", idx)
except Exception:
if sys.version_info.major >= 3 and not isinstance(name, bytes):
name = bytes(name,'ascii')
self.mav.param_request_read_send(self.target_system, self.target_component, name, -1)
def time_since(self, mtype):
'''return the time since the last message of type mtype was received'''
if not mtype in self.messages:
return time.time() - self.start_time
return time.time() - self.messages[mtype]._timestamp
def param_set_send(self, parm_name, parm_value, parm_type=None):
'''wrapper for parameter set'''
if self.mavlink10():
if parm_type is None:
parm_type = mavlink.MAVLINK_TYPE_FLOAT
self.mav.param_set_send(self.target_system, self.target_component,
parm_name.encode('utf8'), parm_value, parm_type)
else:
self.mav.param_set_send(self.target_system, self.target_component,
parm_name.encode('utf8'), parm_value)
def waypoint_request_list_send(self):
'''wrapper for waypoint_request_list_send'''
if self.mavlink10():
self.mav.mission_request_list_send(self.target_system, self.target_component)
else:
self.mav.waypoint_request_list_send(self.target_system, self.target_component)
def waypoint_clear_all_send(self):
'''wrapper for waypoint_clear_all_send'''
if self.mavlink10():
self.mav.mission_clear_all_send(self.target_system, self.target_component)
else:
self.mav.waypoint_clear_all_send(self.target_system, self.target_component)
def waypoint_request_send(self, seq):
'''wrapper for waypoint_request_send'''
if self.mavlink10():
self.mav.mission_request_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_request_send(self.target_system, self.target_component, seq)
def waypoint_set_current_send(self, seq):
'''wrapper for waypoint_set_current_send'''
if self.mavlink10():
self.mav.mission_set_current_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq)
def waypoint_current(self):
'''return current waypoint'''
if self.mavlink10():
m = self.recv_match(type='MISSION_CURRENT', blocking=True)
else:
m = self.recv_match(type='WAYPOINT_CURRENT', blocking=True)
return m.seq
def waypoint_count_send(self, seq):
'''wrapper for waypoint_count_send'''
if self.mavlink10():
self.mav.mission_count_send(self.target_system, self.target_component, seq)
else:
self.mav.waypoint_count_send(self.target_system, self.target_component, seq)
def set_mode_flag(self, flag, enable):
'''
Enables/ disables MAV_MODE_FLAG
@param flag The mode flag,
see MAV_MODE_FLAG enum
@param enable Enable the flag, (True/False)
'''
if self.mavlink10():
mode = self.base_mode
if enable:
mode = mode | flag
elif not enable:
mode = mode & ~flag
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_DO_SET_MODE, 0,
mode,
0, 0, 0, 0, 0, 0)
else:
print("Set mode flag not supported")
def set_mode_auto(self):
'''enter auto mode'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_MISSION_START, 0, 0, 0, 0, 0, 0, 0, 0)
else:
MAV_ACTION_SET_AUTO = 13
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_AUTO)
def mode_mapping(self):
'''return dictionary mapping mode names to numbers, or None if unknown'''
mav_type = self.sysid_state[self.sysid].mav_type
mav_autopilot = self.sysid_state[self.sysid].mav_autopilot
if mav_autopilot == mavlink.MAV_AUTOPILOT_PX4:
return px4_map
if mav_type is None:
return None
return mode_mapping_byname(mav_type)
def set_mode_apm(self, mode, custom_mode = 0, custom_sub_mode = 0):
'''enter arbitrary mode'''
if isinstance(mode, str):
mode_map = self.mode_mapping()
if mode_map is None or mode not in mode_map:
print("Unknown mode '%s'" % mode)
return
mode = mode_map[mode]
# set mode by integer mode number for ArduPilot
self.mav.command_long_send(self.target_system,
self.target_component,
mavlink.MAV_CMD_DO_SET_MODE,
0,
mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
mode,
0,
0,
0,
0,
0)
def set_mode_px4(self, mode, custom_mode, custom_sub_mode):
'''enter arbitrary mode'''
if isinstance(mode, str):
mode_map = self.mode_mapping()
if mode_map is None or mode not in mode_map:
print("Unknown mode '%s'" % mode)
return
# PX4 uses two fields to define modes
mode, custom_mode, custom_sub_mode = px4_map[mode]
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_DO_SET_MODE, 0, mode, custom_mode, custom_sub_mode, 0, 0, 0, 0)
def set_mode(self, mode, custom_mode = 0, custom_sub_mode = 0):
'''set arbitrary flight mode'''
mav_autopilot = self.field('HEARTBEAT', 'autopilot', None)
if mav_autopilot == mavlink.MAV_AUTOPILOT_PX4:
self.set_mode_px4(mode, custom_mode, custom_sub_mode)
else:
self.set_mode_apm(mode)
def set_mode_rtl(self):
'''enter RTL mode'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0, 0, 0, 0, 0, 0)
else:
MAV_ACTION_RETURN = 3
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_RETURN)
def set_mode_manual(self):
'''enter MANUAL mode'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_DO_SET_MODE, 0,
mavlink.MAV_MODE_MANUAL_ARMED,
0, 0, 0, 0, 0, 0)
else:
MAV_ACTION_SET_MANUAL = 12
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_SET_MANUAL)
def set_mode_fbwa(self):
'''enter FBWA mode'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_DO_SET_MODE, 0,
mavlink.MAV_MODE_STABILIZE_ARMED,
0, 0, 0, 0, 0, 0)
else:
print("Forcing FBWA not supported")
def set_mode_loiter(self):
'''enter LOITER mode'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_NAV_LOITER_UNLIM, 0, 0, 0, 0, 0, 0, 0, 0)
else:
MAV_ACTION_LOITER = 27
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_LOITER)
def set_servo(self, channel, pwm):
'''set a servo value'''
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_DO_SET_SERVO, 0,
channel, pwm,
0, 0, 0, 0, 0)
def set_relay(self, relay_pin=0, state=True):
'''Set relay_pin to value of state'''
if self.mavlink10():
self.mav.command_long_send(
self.target_system, # target_system
self.target_component, # target_component
mavlink.MAV_CMD_DO_SET_RELAY, # command
0, # Confirmation
relay_pin, # Relay Number
int(state), # state (1 to indicate arm)
0, # param3 (all other params meaningless)
0, # param4
0, # param5
0, # param6
0) # param7
else:
print("Setting relays not supported.")
def calibrate_level(self):
'''calibrate accels (1D version)'''
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
1, 1, 0, 0, 0, 0, 0)
def calibrate_pressure(self):
'''calibrate pressure'''
if self.mavlink10():
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, 0,
0, 0, 1, 0, 0, 0, 0)
else:
MAV_ACTION_CALIBRATE_PRESSURE = 20
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_CALIBRATE_PRESSURE)
def reboot_autopilot(self, hold_in_bootloader=False, force=False):
'''reboot the autopilot'''
if self.mavlink10():
if hold_in_bootloader:
param1 = 3
else:
param1 = 1
if force:
param6 = 20190226
else:
param6 = 0
self.mav.command_long_send(self.target_system, self.target_component,
mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
param1, 0, 0, 0, 0, param6, 0)
def wait_gps_fix(self):
self.recv_match(type='VFR_HUD', blocking=True)
if self.mavlink10():
self.recv_match(type='GPS_RAW_INT', blocking=True,
condition='GPS_RAW_INT.fix_type>=3 and GPS_RAW_INT.lat != 0')
else:
self.recv_match(type='GPS_RAW', blocking=True,
condition='GPS_RAW.fix_type>=2 and GPS_RAW.lat != 0')
def location(self, relative_alt=False):
'''return current location'''
self.wait_gps_fix()
# wait for another VFR_HUD, to ensure we have correct altitude
self.recv_match(type='VFR_HUD', blocking=True)
self.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
if relative_alt:
alt = self.messages['GLOBAL_POSITION_INT'].relative_alt*0.001
else:
alt = self.messages['VFR_HUD'].alt
return location(self.messages['GPS_RAW_INT'].lat*1.0e-7,
self.messages['GPS_RAW_INT'].lon*1.0e-7,
alt,
self.messages['VFR_HUD'].heading)
def arducopter_arm(self):
'''arm motors (arducopter only)'''
if self.mavlink10():
self.mav.command_long_send(
self.target_system, # target_system
self.target_component,
mavlink.MAV_CMD_COMPONENT_ARM_DISARM, # command
0, # confirmation
1, # param1 (1 to indicate arm)
0, # param2 (all other params meaningless)
0, # param3
0, # param4
0, # param5
0, # param6
0) # param7
def arducopter_disarm(self):
'''disarm motors (arducopter only)'''
if self.mavlink10():
self.mav.command_long_send(
self.target_system, # target_system
self.target_component,
mavlink.MAV_CMD_COMPONENT_ARM_DISARM, # command
0, # confirmation
0, # param1 (0 to indicate disarm)
0, # param2 (all other params meaningless)
0, # param3
0, # param4
0, # param5
0, # param6
0) # param7
def motors_armed(self):
'''return true if motors armed'''
return self.sysid_state[self.sysid].armed
def motors_armed_wait(self):
'''wait for motors to be armed'''
while True:
m = self.wait_heartbeat()
if self.motors_armed():
return
def motors_disarmed_wait(self):
'''wait for motors to be disarmed'''
while True:
m = self.wait_heartbeat()
if not self.motors_armed():
return
def field(self, type, field, default=None):
'''convenient function for returning an arbitrary MAVLink
field with a default'''
if not type in self.messages:
return default
return getattr(self.messages[type], field, default)
def param(self, name, default=None):
'''convenient function for returning an arbitrary MAVLink
parameter with a default'''
if not name in self.params:
return default
return self.params[name]
def setup_signing(self, secret_key, sign_outgoing=True, allow_unsigned_callback=None, initial_timestamp=None, link_id=None):
'''setup for MAVLink2 signing'''
self.mav.signing.secret_key = secret_key
self.mav.signing.sign_outgoing = sign_outgoing
self.mav.signing.allow_unsigned_callback = allow_unsigned_callback
if link_id is None:
# auto-increment the link_id for each link
global global_link_id
link_id = global_link_id
global_link_id = min(global_link_id + 1, 255)
self.mav.signing.link_id = link_id
if initial_timestamp is None:
# timestamp is time since 1/1/2015
epoch_offset = 1420070400
now = max(time.time(), epoch_offset)
initial_timestamp = now - epoch_offset
initial_timestamp = int(initial_timestamp * 100 * 1000)
# initial_timestamp is in 10usec units
self.mav.signing.timestamp = initial_timestamp
def disable_signing(self):
'''disable MAVLink2 signing'''
self.mav.signing.secret_key = None
self.mav.signing.sign_outgoing = False
self.mav.signing.allow_unsigned_callback = None
self.mav.signing.link_id = 0
self.mav.signing.timestamp = 0
def set_close_on_exec(fd):
'''set the close on exec flag on a file descriptor. Ignore exceptions'''
try:
import fcntl
flags = fcntl.fcntl(fd, fcntl.F_GETFD)
flags |= fcntl.FD_CLOEXEC
fcntl.fcntl(fd, fcntl.F_SETFD, flags)
except Exception:
pass
class FakeSerial():
def __init__(self):
pass
def read(self, len):
return ""
def write(self, buf):
raise Exception("write always fails")
def inWaiting(self):
return 0
def close(self):
pass
class mavserial(mavfile):
'''a serial mavlink port'''
def __init__(self, device, baud=115200, autoreconnect=False, source_system=255, source_component=0, use_native=default_native, force_connected=False):
import serial
if ',' in device and not os.path.exists(device):
device, baud = device.split(',')
self.baud = baud
self.device = device
self.autoreconnect = autoreconnect
self.force_connected = force_connected
# we rather strangely set the baudrate initially to 1200, then change to the desired
# baudrate. This works around a kernel bug on some Linux kernels where the baudrate
# is not set correctly
try:
self.port = serial.Serial(self.device, 1200, timeout=0,
dsrdtr=False, rtscts=False, xonxoff=False)
except serial.SerialException as e:
if not force_connected:
raise e
self.port = FakeSerial()
try:
fd = self.port.fileno()
set_close_on_exec(fd)
except Exception:
fd = None
self.set_baudrate(self.baud)
mavfile.__init__(self, fd, device, source_system=source_system, source_component=source_component, use_native=use_native)
self.rtscts = False
def set_rtscts(self, enable):
'''enable/disable RTS/CTS if applicable'''
try:
self.port.setRtsCts(enable)
except Exception:
self.port.rtscts = enable
self.rtscts = enable
def set_baudrate(self, baudrate):
'''set baudrate'''
try:
self.port.setBaudrate(baudrate)
except Exception:
# for pySerial 3.0, which doesn't have setBaudrate()
self.port.baudrate = baudrate
def close(self):