-
Notifications
You must be signed in to change notification settings - Fork 85
/
mavproxy.py
executable file
·1716 lines (1500 loc) · 61 KB
/
mavproxy.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
'''
mavproxy - a MAVLink proxy program
Copyright Andrew Tridgell 2011
Released under the GNU GPL version 3 or later
'''
import sys, os, struct, math, time, socket
import fnmatch, errno, threading
import serial, Queue, select
import logging
# find the mavlink.py module
for d in [ 'pymavlink',
os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', 'pymavlink'),
os.path.join(os.path.dirname(os.path.realpath(__file__)), '..', 'mavlink', 'pymavlink') ]:
if os.path.exists(d):
sys.path.insert(0, d)
if os.name == 'nt':
try:
# broken python compilation of mavlink.py on windows!
os.unlink(os.path.join(d, 'mavlink.pyc'))
except:
pass
# add modules path
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), 'modules'))
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), 'modules', 'lib'))
import select, textconsole
class MPSettings(object):
def __init__(self):
self.vars = [ ('link', int),
('altreadout', int),
('distreadout', int),
('battreadout', int),
('heartbeat', int),
('numcells', int),
('speech', int),
('mavfwd', int),
('mavfwd_rate', int),
('streamrate', int),
('streamrate2', int),
('heartbeatreport', int),
('radiosetup', int),
('paramretry', int),
('moddebug', int),
('rc1mul', int),
('rc2mul', int),
('rc4mul', int)]
self.link = 1
self.altreadout = 10
self.distreadout = 200
self.battreadout = 0
self.basealtitude = -1
self.heartbeat = 1
self.numcells = 0
self.mavfwd = 1
self.mavfwd_rate = 0
self.speech = 0
self.streamrate = 4
self.streamrate2 = 4
self.radiosetup = 0
self.heartbeatreport = 1
self.paramretry = 10
self.rc1mul = 1
self.rc2mul = 1
self.rc4mul = 1
self.moddebug = 2
def set(self, vname, value):
'''set a setting'''
for (v,t) in sorted(self.vars):
if v == vname:
try:
value = t(value)
except:
print("Unable to convert %s to type %s" % (value, t))
return
setattr(self, vname, value)
return
def show(self, v):
'''show settings'''
print("%20s %s" % (v, getattr(self, v)))
def show_all(self):
'''show all settings'''
for (v,t) in sorted(self.vars):
self.show(v)
class MPStatus(object):
'''hold status information about the mavproxy'''
def __init__(self):
if opts.quadcopter:
self.rc_throttle = [ 0.0, 0.0, 0.0, 0.0 ]
else:
self.rc_aileron = 0
self.rc_elevator = 0
self.rc_throttle = 0
self.rc_rudder = 0
self.gps = None
self.msgs = {}
self.msg_count = {}
self.counters = {'MasterIn' : [], 'MasterOut' : 0, 'FGearIn' : 0, 'FGearOut' : 0, 'Slave' : 0}
self.setup_mode = opts.setup
self.wp_op = None
self.wp_save_filename = None
self.wploader = mavwp.MAVWPLoader()
self.fenceloader = mavwp.MAVFenceLoader()
self.loading_waypoints = False
self.loading_waypoint_lasttime = time.time()
self.mav_error = 0
self.target_system = 1
self.target_component = 1
self.speech = None
self.altitude = 0
self.last_altitude_announce = 0.0
self.last_distance_announce = 0.0
self.last_battery_announce = 0
self.last_avionics_battery_announce = 0
self.battery_level = -1
self.avionics_battery_level = -1
self.last_waypoint = 0
self.exit = False
self.override = [ 0 ] * 8
self.last_override = [ 0 ] * 8
self.override_counter = 0
self.flightmode = 'MAV'
self.logdir = None
self.last_heartbeat = 0
self.heartbeat_error = False
self.last_apm_msg = None
self.highest_usec = 0
self.fence_enabled = False
self.last_fence_breach = 0
self.last_fence_status = 0
self.have_gps_lock = False
self.lost_gps_lock = False
self.watch = None
self.last_streamrate1 = -1
self.last_streamrate2 = -1
self.last_paramretry = 0
self.last_seq = 0
def show(self, f, pattern=None):
'''write status to status.txt'''
if pattern is None:
f.write('Counters: ')
for c in self.counters:
f.write('%s:%s ' % (c, self.counters[c]))
f.write('\n')
f.write('MAV Errors: %u\n' % self.mav_error)
f.write(str(self.gps)+'\n')
for m in sorted(self.msgs.keys()):
if pattern is not None and not fnmatch.fnmatch(str(m).upper(), pattern.upper()):
continue
f.write("%u: %s\n" % (self.msg_count[m], str(self.msgs[m])))
def write(self):
'''write status to status.txt'''
f = open('status.txt', mode='w')
self.show(f)
f.close()
class MAVFunctions(object):
pass
class MPState(object):
'''holds state of mavproxy'''
def __init__(self):
self.console = textconsole.SimpleConsole()
self.map = None
self.settings = MPSettings()
self.status = MPStatus()
# master mavlink device
self.mav_master = None
# mavlink outputs
self.mav_outputs = []
# SITL output
self.sitl_output = None
self.mav_param = {}
self.modules = []
self.functions = MAVFunctions()
self.functions.say = say
self.functions.process_stdin = process_stdin
self.select_extra = {}
self.msg_queue = Queue.Queue()
def queue_message(self, message):
logging.info('Queueing message %s', message)
self.msg_queue.put(message)
def master(self):
'''return the currently chosen mavlink master object'''
if self.settings.link > len(self.mav_master):
self.settings.link = 1
# try to use one with no link error
if not self.mav_master[self.settings.link-1].linkerror:
return self.mav_master[self.settings.link-1]
for m in self.mav_master:
if not m.linkerror:
return m
return self.mav_master[self.settings.link-1]
def get_usec():
'''time since 1970 in microseconds'''
return int(time.time() * 1.0e6)
class rline(object):
'''async readline abstraction'''
def __init__(self, prompt):
import threading
self.prompt = prompt
self.line = None
try:
import readline
except Exception:
pass
def set_prompt(self, prompt):
if prompt != self.prompt:
self.prompt = prompt
sys.stdout.write(prompt)
def say(text, priority='important'):
'''speak some text'''
''' http://cvs.freebsoft.org/doc/speechd/ssip.html see 4.3.1 for priorities'''
mpstate.console.writeln(text)
if mpstate.settings.speech:
import speechd
mpstate.status.speech = speechd.SSIPClient('MAVProxy%u' % os.getpid())
mpstate.status.speech.set_output_module('festival')
mpstate.status.speech.set_language('en')
mpstate.status.speech.set_priority(priority)
mpstate.status.speech.set_punctuation(speechd.PunctuationMode.SOME)
mpstate.status.speech.speak(text)
mpstate.status.speech.close()
def get_mav_param(param, default=None):
'''return a EEPROM parameter value'''
if not param in mpstate.mav_param:
return default
return mpstate.mav_param[param]
def send_rc_override():
'''send RC override packet'''
if mpstate.sitl_output:
buf = struct.pack('<HHHHHHHH',
*mpstate.status.override)
mpstate.sitl_output.write(buf)
else:
mpstate.master().mav.rc_channels_override_send(mpstate.status.target_system,
mpstate.status.target_component,
*mpstate.status.override)
def cmd_switch(args):
'''handle RC switch changes'''
mapping = [ 0, 1165, 1295, 1425, 1555, 1685, 1815 ]
if len(args) != 1:
print("Usage: switch <pwmvalue>")
return
value = int(args[0])
if value < 0 or value > 6:
print("Invalid switch value. Use 1-6 for flight modes, '0' to disable")
return
if opts.quadcopter:
default_channel = 5
else:
default_channel = 8
flite_mode_ch_parm = int(get_mav_param("FLTMODE_CH", default_channel))
mpstate.status.override[flite_mode_ch_parm-1] = mapping[value]
mpstate.status.override_counter = 10
send_rc_override()
if value == 0:
print("Disabled RC switch override")
else:
print("Set RC switch override to %u (PWM=%u channel=%u)" % (
value, mapping[value], flite_mode_ch_parm))
def cmd_trim(args):
'''trim aileron, elevator and rudder to current values'''
if not 'RC_CHANNELS_RAW' in mpstate.status.msgs:
print("No RC_CHANNELS_RAW to trim with")
return
m = mpstate.status.msgs['RC_CHANNELS_RAW']
mpstate.master().param_set_send('ROLL_TRIM', m.chan1_raw)
mpstate.master().param_set_send('PITCH_TRIM', m.chan2_raw)
mpstate.master().param_set_send('YAW_TRIM', m.chan4_raw)
print("Trimmed to aileron=%u elevator=%u rudder=%u" % (
m.chan1_raw, m.chan2_raw, m.chan4_raw))
def cmd_rc(args):
'''handle RC value override'''
if len(args) != 2:
print("Usage: rc <channel> <pwmvalue>")
return
channel = int(args[0])
value = int(args[1])
if value == -1:
value = 65535
if channel < 1 or channel > 8:
print("Channel must be between 1 and 8")
return
mpstate.status.override[channel-1] = value
mpstate.status.override_counter = 10
send_rc_override()
def cmd_loiter(args):
'''set LOITER mode'''
mpstate.master().set_mode_loiter()
def cmd_auto(args):
'''set AUTO mode'''
mpstate.master().set_mode_auto()
def cmd_ground(args):
'''do a ground start mode'''
mpstate.master().calibrate_imu()
def cmd_level(args):
'''do a ground start mode'''
mpstate.master().calibrate_level()
def cmd_rtl(args):
'''set RTL mode'''
mpstate.master().set_mode_rtl()
def cmd_manual(args):
'''set MANUAL mode'''
MAV_ACTION_SET_MANUAL = 12
mpstate.master().mav.action_send(mpstate.status.target_system, mpstate.status.target_component, MAV_ACTION_SET_MANUAL)
def process_waypoint_request(m, master):
'''process a waypoint request from the master'''
if (not mpstate.status.loading_waypoints or
time.time() > mpstate.status.loading_waypoint_lasttime + 10.0):
mpstate.status.loading_waypoints = False
mpstate.console.error("not loading waypoints")
return
if m.seq >= mpstate.status.wploader.count():
mpstate.console.error("Request for bad waypoint %u (max %u)" % (m.seq, mpstate.status.wploader.count()))
return
master.mav.send(mpstate.status.wploader.wp(m.seq))
mpstate.status.loading_waypoint_lasttime = time.time()
mpstate.console.writeln("Sent waypoint %u : %s" % (m.seq, mpstate.status.wploader.wp(m.seq)))
if m.seq == mpstate.status.wploader.count() - 1:
mpstate.status.loading_waypoints = False
mpstate.console.writeln("Sent all %u waypoints" % mpstate.status.wploader.count())
def load_waypoints(filename):
'''load waypoints from a file'''
mpstate.status.wploader.target_system = mpstate.status.target_system
mpstate.status.wploader.target_component = mpstate.status.target_component
try:
mpstate.status.wploader.load(filename)
except Exception, msg:
print("Unable to load %s - %s" % (filename, msg))
return
print("Loaded %u waypoints from %s" % (mpstate.status.wploader.count(), filename))
mpstate.master().waypoint_clear_all_send()
if mpstate.status.wploader.count() == 0:
return
mpstate.status.loading_waypoints = True
mpstate.status.loading_waypoint_lasttime = time.time()
mpstate.master().waypoint_count_send(mpstate.status.wploader.count())
def save_waypoints(filename):
'''save waypoints to a file'''
try:
mpstate.status.wploader.save(filename)
except Exception, msg:
print("Failed to save %s - %s" % (filename, msg))
return
print("Saved %u waypoints to %s" % (mpstate.status.wploader.count(), filename))
def cmd_wp(args):
'''waypoint commands'''
if len(args) < 1:
print("usage: wp <list|load|save|set|clear>")
return
if args[0] == "load":
if len(args) != 2:
print("usage: wp load <filename>")
return
load_waypoints(args[1])
elif args[0] == "list":
mpstate.status.wp_op = "list"
mpstate.master().waypoint_request_list_send()
elif args[0] == "save":
if len(args) != 2:
print("usage: wp save <filename>")
return
mpstate.status.wp_save_filename = args[1]
mpstate.status.wp_op = "save"
mpstate.master().waypoint_request_list_send()
elif args[0] == "set":
if len(args) != 2:
print("usage: wp set <wpindex>")
return
mpstate.master().waypoint_set_current_send(int(args[1]))
elif args[0] == "clear":
mpstate.master().waypoint_clear_all_send()
else:
print("Usage: wp <list|load|save|set|clear>")
def fetch_fence_point(i):
'''fetch one fence point'''
mpstate.master().mav.fence_fetch_point_send(mpstate.status.target_system,
mpstate.status.target_component, i)
tstart = time.time()
p = None
while time.time() - tstart < 1:
p = mpstate.master().recv_match(type='FENCE_POINT', blocking=False)
if p is not None:
break
time.sleep(0.1)
continue
if p is None:
mpstate.console.error("Failed to fetch point %u" % i)
return None
return p
def load_fence(filename):
'''load fence points from a file'''
try:
mpstate.status.fenceloader.target_system = mpstate.status.target_system
mpstate.status.fenceloader.target_component = mpstate.status.target_component
mpstate.status.fenceloader.load(filename)
except Exception, msg:
print("Unable to load %s - %s" % (filename, msg))
return
print("Loaded %u geo-fence points from %s" % (mpstate.status.fenceloader.count(), filename))
# must disable geo-fencing when loading
action = get_mav_param('FENCE_ACTION', mavutil.mavlink.FENCE_ACTION_NONE)
param_set('FENCE_ACTION', mavutil.mavlink.FENCE_ACTION_NONE)
param_set('FENCE_TOTAL', mpstate.status.fenceloader.count())
for i in range(mpstate.status.fenceloader.count()):
p = mpstate.status.fenceloader.point(i)
mpstate.master().mav.send(p)
p2 = fetch_fence_point(i)
if p2 is None:
param_set('FENCE_ACTION', action)
return
if (p.idx != p2.idx or
abs(p.lat - p2.lat) >= 0.00001 or
abs(p.lng - p2.lng) >= 0.00001):
print("Failed to send fence point %u" % i)
param_set('FENCE_ACTION', action)
return
param_set('FENCE_ACTION', action)
def list_fence(filename):
'''list fence points, optionally saving to a file'''
mpstate.status.fenceloader.clear()
count = get_mav_param('FENCE_TOTAL', 0)
if count == 0:
print("No geo-fence points")
return
for i in range(int(count)):
p = fetch_fence_point(i)
if p is None:
return
mpstate.status.fenceloader.add(p)
if filename is not None:
try:
mpstate.status.fenceloader.save(filename)
except Exception, msg:
print("Unable to save %s - %s" % (filename, msg))
return
print("Saved %u geo-fence points to %s" % (mpstate.status.fenceloader.count(), filename))
else:
for i in range(mpstate.status.fenceloader.count()):
p = mpstate.status.fenceloader.point(i)
mpstate.console.writeln("lat=%f lng=%f" % (p.lat, p.lng))
def cmd_fence(args):
'''geo-fence commands'''
if len(args) < 1:
print("usage: fence <list|load|save|clear>")
return
if args[0] == "load":
if len(args) != 2:
print("usage: fence load <filename>")
return
load_fence(args[1])
elif args[0] == "list":
list_fence(None)
elif args[0] == "save":
if len(args) != 2:
print("usage: fence save <filename>")
return
list_fence(args[1])
elif args[0] == "clear":
param_set('FENCE_TOTAL', 0)
else:
print("Usage: fence <list|load|save|clear>")
def param_set(name, value, retries=3):
'''set a parameter'''
got_ack = False
while retries > 0 and not got_ack:
retries -= 1
mpstate.master().param_set_send(name.upper(), float(value))
tstart = time.time()
while time.time() - tstart < 1:
ack = mpstate.master().recv_match(type='PARAM_VALUE', blocking=False)
if ack == None:
time.sleep(0.1)
continue
if str(name).upper() == str(ack.param_id).upper():
got_ack = True
break
if not got_ack:
print("timeout setting %s to %f" % (name, float(value)))
return False
return True
def param_save(filename, wildcard):
'''save parameters to a file'''
f = open(filename, mode='w')
k = mpstate.mav_param.keys()
k.sort()
count = 0
for p in k:
if p and fnmatch.fnmatch(str(p).upper(), wildcard.upper()):
f.write("%-15.15s %f\n" % (p, mpstate.mav_param[p]))
count += 1
f.close()
print("Saved %u parameters to %s" % (count, filename))
def param_load_file(filename, wildcard):
'''load parameters from a file'''
try:
f = open(filename, mode='r')
except:
print("Failed to open file '%s'" % filename)
return
count = 0
changed = 0
for line in f:
line = line.strip()
if not line or line[0] == "#":
continue
a = line.split()
if len(a) != 2:
print("Invalid line: %s" % line)
continue
# some parameters should not be loaded from file
if a[0] in ['SYSID_SW_MREV', 'SYS_NUM_RESETS', 'ARSPD_OFFSET', 'GND_ABS_PRESS',
'GND_TEMP', 'CMD_TOTAL', 'CMD_INDEX', 'LOG_LASTFILE', 'FENCE_TOTAL',
'FORMAT_VERSION' ]:
continue
if not fnmatch.fnmatch(a[0].upper(), wildcard.upper()):
continue
if a[0] not in mpstate.mav_param:
print("Unknown parameter %s" % a[0])
continue
old_value = mpstate.mav_param[a[0]]
if math.fabs(old_value - float(a[1])) > 0.000001:
if param_set(a[0], a[1]):
print("changed %s from %f to %f" % (a[0], old_value, float(a[1])))
changed += 1
count += 1
f.close()
print("Loaded %u parameters from %s (changed %u)" % (count, filename, changed))
param_wildcard = "*"
def cmd_param(args):
'''control parameters'''
if len(args) < 1:
print("usage: param <fetch|edit|set|show>")
return
if args[0] == "fetch":
mpstate.master().param_fetch_all()
print("Requested parameter list")
elif args[0] == "save":
if len(args) < 2:
print("usage: param save <filename> [wildcard]")
return
if len(args) > 2:
param_wildcard = args[2]
else:
param_wildcard = "*"
param_save(args[1], param_wildcard)
elif args[0] == "set":
if len(args) != 3:
print("Usage: param set PARMNAME VALUE")
return
param = args[1]
value = args[2]
if not param.upper() in mpstate.mav_param:
print("Unable to find parameter '%s'" % param)
return
param_set(param, value)
elif args[0] == "load":
if len(args) < 2:
print("Usage: param load <filename> [wildcard]")
return
if len(args) > 2:
param_wildcard = args[2]
else:
param_wildcard = "*"
param_load_file(args[1], param_wildcard)
elif args[0] == "show":
if len(args) > 1:
pattern = args[1]
else:
pattern = "*"
k = sorted(mpstate.mav_param.keys())
for p in k:
if fnmatch.fnmatch(str(p).upper(), pattern.upper()):
print("%-15.15s %f" % (str(p), mpstate.mav_param[p]))
else:
print("Unknown subcommand '%s' (try 'fetch', 'save', 'set', 'show', 'load')" % args[0])
def cmd_set(args):
'''control mavproxy options'''
if len(args) == 0:
mpstate.settings.show_all()
return
if getattr(mpstate.settings, args[0], None) is None:
print("Unknown setting '%s'" % args[0])
return
if len(args) == 1:
mpstate.settings.show(args[0])
else:
mpstate.settings.set(args[0], args[1])
def cmd_status(args):
'''show status'''
if len(args) == 0:
mpstate.status.show(sys.stdout, pattern=None)
else:
for pattern in args:
mpstate.status.show(sys.stdout, pattern=pattern)
def cmd_bat(args):
'''show battery levels'''
print("Flight battery: %u%%" % mpstate.status.battery_level)
print("Avionics battery: %u%%" % mpstate.status.avionics_battery_level)
def cmd_alt(args):
'''show altitude'''
print("Altitude: %.1f" % mpstate.status.altitude)
def cmd_up(args):
'''adjust TRIM_PITCH_CD up by 5 degrees'''
if len(args) == 0:
adjust = 5.0
else:
adjust = float(args[0])
old_trim = get_mav_param('TRIM_PITCH_CD', None)
if old_trim is None:
print("Existing trim value unknown!")
return
new_trim = int(old_trim + (adjust*100))
if math.fabs(new_trim - old_trim) > 1000:
print("Adjustment by %d too large (from %d to %d)" % (adjust*100, old_trim, new_trim))
return
print("Adjusting TRIM_PITCH_CD from %d to %d" % (old_trim, new_trim))
param_set('TRIM_PITCH_CD', new_trim)
def cmd_setup(args):
mpstate.status.setup_mode = True
mpstate.rl.set_prompt("")
def cmd_reset(args):
print("Resetting master")
mpstate.master().reset()
def cmd_link(args):
for master in mpstate.mav_master:
linkdelay = (mpstate.status.highest_usec - master.highest_usec)*1e-6
if master.linkerror:
print("link %u down" % (master.linknum+1))
elif master.link_delayed:
print("link %u delayed by %.2f seconds" % (master.linknum+1, linkdelay))
else:
print("link %u OK (%u packets, %.2fs delay, %u lost, %.1f%% loss)" % (master.linknum+1,
mpstate.status.counters['MasterIn'][master.linknum],
linkdelay,
master.mav_loss,
master.packet_loss()))
def cmd_watch(args):
'''watch a mavlink packet pattern'''
if len(args) == 0:
mpstate.status.watch = None
return
mpstate.status.watch = args[0]
print("Watching %s" % mpstate.status.watch)
def cmd_module(args):
'''module commands'''
usage = "usage: module <list|load|reload>"
if len(args) < 1:
print(usage)
return
if args[0] == "list":
for m in mpstate.modules:
print("%s: %s" % (m.name(), m.description()))
elif args[0] == "load":
if len(args) < 2:
print("usage: module load <name>")
return
try:
directory = os.path.dirname(args[1])
modname = os.path.basename(args[1])
if directory:
sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)),
'modules', directory))
m = __import__(modname)
if m in mpstate.modules:
raise RuntimeError("module already loaded")
m.init(mpstate)
mpstate.modules.append(m)
print("Loaded module %s" % modname)
except Exception, msg:
print("Unable to load module %s: %s" % (modname, msg))
raise
elif args[0] == "reload":
if len(args) < 2:
print("usage: module reload <name>")
return
modname = os.path.basename(args[1])
for m in mpstate.modules:
if m.name() == modname:
try:
m.unload()
except Exception:
pass
reload(m)
m.init(mpstate)
print("Reloaded module %s" % modname)
return
print("Unable to find module %s" % modname)
else:
print(usage)
command_map = {
'switch' : (cmd_switch, 'set RC switch (1-5), 0 disables'),
'rc' : (cmd_rc, 'override a RC channel value'),
'wp' : (cmd_wp, 'waypoint management'),
'fence' : (cmd_fence, 'geo-fence management'),
'param' : (cmd_param, 'manage APM parameters'),
'setup' : (cmd_setup, 'go into setup mode'),
'reset' : (cmd_reset, 'reopen the connection to the MAVLink master'),
'status' : (cmd_status, 'show status'),
'trim' : (cmd_trim, 'trim aileron, elevator and rudder to current values'),
'auto' : (cmd_auto, 'set AUTO mode'),
'ground' : (cmd_ground, 'do a ground start'),
'level' : (cmd_level, 'set level on a multicopter'),
'loiter' : (cmd_loiter, 'set LOITER mode'),
'rtl' : (cmd_rtl, 'set RTL mode'),
'manual' : (cmd_manual, 'set MANUAL mode'),
'set' : (cmd_set, 'mavproxy settings'),
'bat' : (cmd_bat, 'show battery levels'),
'alt' : (cmd_alt, 'show relative altitude'),
'link' : (cmd_link, 'show link status'),
'up' : (cmd_up, 'adjust TRIM_PITCH_CD up by 5 degrees'),
'watch' : (cmd_watch, 'watch a MAVLink pattern'),
'module' : (cmd_module, 'module commands'),
}
def process_stdin(line):
'''handle commands from user'''
if line is None:
sys.exit(0)
line = line.strip()
if mpstate.status.setup_mode:
# in setup mode we send strings straight to the master
if line == '.':
mpstate.status.setup_mode = False
mpstate.status.flightmode = "MAV"
mpstate.rl.set_prompt("MAV> ")
return
if line == '+++':
mpstate.master().write(line)
else:
mpstate.master().write(line + '\r')
return
if not line:
return
args = line.split()
cmd = args[0]
if cmd == 'help':
k = command_map.keys()
k.sort()
for cmd in k:
(fn, help) = command_map[cmd]
print("%-15s : %s" % (cmd, help))
return
if not cmd in command_map:
print("Unknown command '%s'" % line)
return
(fn, help) = command_map[cmd]
try:
fn(args[1:])
except Exception as e:
print("ERROR in command: %s" % str(e))
def scale_rc(servo, min, max, param):
'''scale a PWM value'''
# default to servo range of 1000 to 2000
min_pwm = get_mav_param('%s_MIN' % param, 0)
max_pwm = get_mav_param('%s_MAX' % param, 0)
if min_pwm == 0 or max_pwm == 0:
return 0
if max_pwm == min_pwm:
p = 0.0
else:
p = (servo-min_pwm) / float(max_pwm-min_pwm)
v = min + p*(max-min)
if v < min:
v = min
if v > max:
v = max
return v
def system_check():
'''check that the system is ready to fly'''
ok = True
if mavutil.mavlink.WIRE_PROTOCOL_VERSION == '1.0':
if not 'GPS_RAW_INT' in mpstate.status.msgs:
say("WARNING no GPS status")
return
if mpstate.status.msgs['GPS_RAW_INT'].fix_type != 3:
say("WARNING no GPS lock")
ok = False
else:
if not 'GPS_RAW' in mpstate.status.msgs and not 'GPS_RAW_INT' in mpstate.status.msgs:
say("WARNING no GPS status")
return
if mpstate.status.msgs['GPS_RAW'].fix_type != 2:
say("WARNING no GPS lock")
ok = False
if not 'PITCH_MIN' in mpstate.mav_param:
say("WARNING no pitch parameter available")
return
if int(mpstate.mav_param['PITCH_MIN']) > 1300:
say("WARNING PITCH MINIMUM not set")
ok = False
if not 'ATTITUDE' in mpstate.status.msgs:
say("WARNING no attitude recorded")
return
if math.fabs(mpstate.status.msgs['ATTITUDE'].pitch) > math.radians(5):
say("WARNING pitch is %u degrees" % math.degrees(mpstate.status.msgs['ATTITUDE'].pitch))
ok = False
if math.fabs(mpstate.status.msgs['ATTITUDE'].roll) > math.radians(5):
say("WARNING roll is %u degrees" % math.degrees(mpstate.status.msgs['ATTITUDE'].roll))
ok = False
if ok:
say("All OK SYSTEM READY TO FLY")
def beep():
f = open("/dev/tty", mode="w")
f.write(chr(7))
f.close()
def vcell_to_battery_percent(vcell):
'''convert a cell voltage to a percentage battery level'''
if vcell > 4.1:
# above 4.1 is 100% battery
return 100.0
elif vcell > 3.81:
# 3.81 is 17% remaining, from flight logs
return 17.0 + 83.0 * (vcell - 3.81) / (4.1 - 3.81)
elif vcell > 3.81:
# below 3.2 it degrades fast. It's dead at 3.2
return 0.0 + 17.0 * (vcell - 3.20) / (3.81 - 3.20)
# it's dead or disconnected
return 0.0
def battery_update(SYS_STATUS):
'''update battery level'''
# main flight battery
mpstate.status.battery_level = SYS_STATUS.battery_remaining/10.0
# avionics battery
if not 'AP_ADC' in mpstate.status.msgs:
return
rawvalue = float(mpstate.status.msgs['AP_ADC'].adc2)
INPUT_VOLTAGE = 4.68
VOLT_DIV_RATIO = 3.56
voltage = rawvalue*(INPUT_VOLTAGE/1024.0)*VOLT_DIV_RATIO
vcell = voltage / mpstate.settings.numcells
avionics_battery_level = vcell_to_battery_percent(vcell)
if mpstate.status.avionics_battery_level == -1 or abs(avionics_battery_level-mpstate.status.avionics_battery_level) > 70:
mpstate.status.avionics_battery_level = avionics_battery_level
else:
mpstate.status.avionics_battery_level = (95*mpstate.status.avionics_battery_level + 5*avionics_battery_level)/100
def battery_report():
'''report battery level'''
if int(mpstate.settings.battreadout) == 0:
return
rbattery_level = int((mpstate.status.battery_level+5)/10)*10
if rbattery_level != mpstate.status.last_battery_announce:
say("Flight battery %u percent" % rbattery_level,priority='notification')
mpstate.status.last_battery_announce = rbattery_level
if rbattery_level <= 20:
say("Flight battery warning")
# avionics battery reporting disabled for now
return
avionics_rbattery_level = int((mpstate.status.avionics_battery_level+5)/10)*10
if avionics_rbattery_level != mpstate.status.last_avionics_battery_announce:
say("Avionics Battery %u percent" % avionics_rbattery_level,priority='notification')
mpstate.status.last_avionics_battery_announce = avionics_rbattery_level
if avionics_rbattery_level <= 20:
say("Avionics battery warning")
def handle_usec_timestamp(m, master):
'''special handling for MAVLink packets with a usec field'''
usec = m.time_usec
if usec + 6.0e7 < master.highest_usec:
say('Time has wrapped')
mpstate.console.writeln("usec %u highest_usec %u" % (usec, master.highest_usec))
mpstate.status.highest_usec = usec
for mm in mpstate.mav_master:
mm.link_delayed = False
mm.highest_usec = usec
return
# we want to detect when a link has significant buffering, causing us to receive
# old packets. If we get packets that are more than 1 second old, then mark the link
# as being delayed. We will not act on packets from this link until it has caught up
master.highest_usec = usec
if usec > mpstate.status.highest_usec:
mpstate.status.highest_usec = usec
if usec + 1e6 < mpstate.status.highest_usec and not master.link_delayed and len(mpstate.mav_master) > 1:
master.link_delayed = True
mpstate.console.writeln("link %u delayed" % (master.linknum+1))
elif usec + 0.5e6 > mpstate.status.highest_usec and master.link_delayed:
master.link_delayed = False
mpstate.console.writeln("link %u OK" % (master.linknum+1))
def report_altitude(altitude):
'''possibly report a new altitude'''
mpstate.status.altitude = altitude
if (int(mpstate.settings.altreadout) > 0 and
math.fabs(mpstate.status.altitude - mpstate.status.last_altitude_announce) >= int(mpstate.settings.altreadout)):