-
Notifications
You must be signed in to change notification settings - Fork 125
/
Quadcopter.py
5325 lines (4458 loc) · 262 KB
/
Quadcopter.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
####################################################################################################
####################################################################################################
## ##
## Hove's Raspberry Pi Python Quadcopter Flight Controller. Open Source @ GitHub ##
## PiStuffing/Quadcopter under GPL for non-commercial application. Any code derived from ##
## this should retain this copyright comment. ##
## ##
## Copyright 2012 - 2018 Andy Baker (Hove) - [email protected] ##
## ##
####################################################################################################
####################################################################################################
from __future__ import division
from __future__ import with_statement
import signal
import socket
import time
import sys
import getopt
import math
from array import *
import smbus
import select
import os
import io
import logging
import csv
from RPIO import PWM
import RPi.GPIO as GPIO
import subprocess
import ctypes
from ctypes.util import find_library
import picamera
import struct
import gps
import serial
MIN_SATS = 7
EARTH_RADIUS = 6371000 # meters
GRAV_ACCEL = 9.80665 # meters per second per second
RC_PASSIVE = 0
RC_TAKEOFF = 1
RC_FLYING = 2
RC_LANDING = 3
RC_DONE = 4
RC_ABORT = 5
rc_status_name = ["PASSIVE", "TAKEOFF", "FLYING", "LANDING", "DONE", "ABORT"]
FULL_FIFO_BATCHES = 20 # << int(512 / 12)
####################################################################################################
#
# Adafruit i2c interface enhanced with performance / error handling enhancements
#
####################################################################################################
class I2C:
def __init__(self, address, bus=smbus.SMBus(1)):
self.address = address
self.bus = bus
self.misses = 0
def writeByte(self, value):
self.bus.write_byte(self.address, value)
def write8(self, reg, value):
self.bus.write_byte_data(self.address, reg, value)
def writeList(self, reg, list):
self.bus.write_i2c_block_data(self.address, reg, list)
def readU8(self, reg):
result = self.bus.read_byte_data(self.address, reg)
return result
def readS8(self, reg):
result = self.bus.read_byte_data(self.address, reg)
result = result - 256 if result > 127 else result
return result
def readU16(self, reg):
hibyte = self.bus.read_byte_data(self.address, reg)
result = (hibyte << 8) + self.bus.read_byte_data(self.address, reg+1)
return result
def readS16(self, reg):
hibyte = self.bus.read_byte_data(self.address, reg)
hibyte = hibyte - 256 if hibyte > 127 else hibyte
result = (hibyte << 8) + self.bus.read_byte_data(self.address, reg+1)
return result
def readList(self, reg, length):
"Reads a byte array value from the I2C device. The content depends on the device. The "
"FIFO read return sequential values from the same register. For all other, sequestial"
"regester values are returned"
result = self.bus.read_i2c_block_data(self.address, reg, length)
return result
####################################################################################################
#
# Gyroscope / Accelerometer class for reading position / movement. Works with the Invensense IMUs:
#
# - MPU-6050
# - MPU-9150
# - MPU-9250
#
####################################################################################################
class MPU6050:
i2c = None
# Registers/etc.
__MPU6050_RA_SELF_TEST_XG = 0x00
__MPU6050_RA_SELF_TEST_YG = 0x01
__MPU6050_RA_SELF_TEST_ZG = 0x02
__MPU6050_RA_SELF_TEST_XA = 0x0D
__MPU6050_RA_SELF_TEST_YA = 0x0E
__MPU6050_RA_SELF_TEST_ZA = 0x0F
__MPU6050_RA_XG_OFFS_USRH = 0x13
__MPU6050_RA_XG_OFFS_USRL = 0x14
__MPU6050_RA_YG_OFFS_USRH = 0x15
__MPU6050_RA_YG_OFFS_USRL = 0x16
__MPU6050_RA_ZG_OFFS_USRH = 0x17
__MPU6050_RA_ZG_OFFS_USRL = 0x18
__MPU6050_RA_SMPLRT_DIV = 0x19
__MPU6050_RA_CONFIG = 0x1A
__MPU6050_RA_GYRO_CONFIG = 0x1B
__MPU6050_RA_ACCEL_CONFIG = 0x1C
__MPU9250_RA_ACCEL_CFG_2 = 0x1D
__MPU6050_RA_FF_THR = 0x1D
__MPU6050_RA_FF_DUR = 0x1E
__MPU6050_RA_MOT_THR = 0x1F
__MPU6050_RA_MOT_DUR = 0x20
__MPU6050_RA_ZRMOT_THR = 0x21
__MPU6050_RA_ZRMOT_DUR = 0x22
__MPU6050_RA_FIFO_EN = 0x23
__MPU6050_RA_I2C_MST_CTRL = 0x24
__MPU6050_RA_I2C_SLV0_ADDR = 0x25
__MPU6050_RA_I2C_SLV0_REG = 0x26
__MPU6050_RA_I2C_SLV0_CTRL = 0x27
__MPU6050_RA_I2C_SLV1_ADDR = 0x28
__MPU6050_RA_I2C_SLV1_REG = 0x29
__MPU6050_RA_I2C_SLV1_CTRL = 0x2A
__MPU6050_RA_I2C_SLV2_ADDR = 0x2B
__MPU6050_RA_I2C_SLV2_REG = 0x2C
__MPU6050_RA_I2C_SLV2_CTRL = 0x2D
__MPU6050_RA_I2C_SLV3_ADDR = 0x2E
__MPU6050_RA_I2C_SLV3_REG = 0x2F
__MPU6050_RA_I2C_SLV3_CTRL = 0x30
__MPU6050_RA_I2C_SLV4_ADDR = 0x31
__MPU6050_RA_I2C_SLV4_REG = 0x32
__MPU6050_RA_I2C_SLV4_DO = 0x33
__MPU6050_RA_I2C_SLV4_CTRL = 0x34
__MPU6050_RA_I2C_SLV4_DI = 0x35
__MPU6050_RA_I2C_MST_STATUS = 0x36
__MPU6050_RA_INT_PIN_CFG = 0x37
__MPU6050_RA_INT_ENABLE = 0x38
__MPU6050_RA_DMP_INT_STATUS = 0x39
__MPU6050_RA_INT_STATUS = 0x3A
__MPU6050_RA_ACCEL_XOUT_H = 0x3B
__MPU6050_RA_ACCEL_XOUT_L = 0x3C
__MPU6050_RA_ACCEL_YOUT_H = 0x3D
__MPU6050_RA_ACCEL_YOUT_L = 0x3E
__MPU6050_RA_ACCEL_ZOUT_H = 0x3F
__MPU6050_RA_ACCEL_ZOUT_L = 0x40
__MPU6050_RA_TEMP_OUT_H = 0x41
__MPU6050_RA_TEMP_OUT_L = 0x42
__MPU6050_RA_GYRO_XOUT_H = 0x43
__MPU6050_RA_GYRO_XOUT_L = 0x44
__MPU6050_RA_GYRO_YOUT_H = 0x45
__MPU6050_RA_GYRO_YOUT_L = 0x46
__MPU6050_RA_GYRO_ZOUT_H = 0x47
__MPU6050_RA_GYRO_ZOUT_L = 0x48
__MPU6050_RA_EXT_SENS_DATA_00 = 0x49
__MPU6050_RA_EXT_SENS_DATA_01 = 0x4A
__MPU6050_RA_EXT_SENS_DATA_02 = 0x4B
__MPU6050_RA_EXT_SENS_DATA_03 = 0x4C
__MPU6050_RA_EXT_SENS_DATA_04 = 0x4D
__MPU6050_RA_EXT_SENS_DATA_05 = 0x4E
__MPU6050_RA_EXT_SENS_DATA_06 = 0x4F
__MPU6050_RA_EXT_SENS_DATA_07 = 0x50
__MPU6050_RA_EXT_SENS_DATA_08 = 0x51
__MPU6050_RA_EXT_SENS_DATA_09 = 0x52
__MPU6050_RA_EXT_SENS_DATA_10 = 0x53
__MPU6050_RA_EXT_SENS_DATA_11 = 0x54
__MPU6050_RA_EXT_SENS_DATA_12 = 0x55
__MPU6050_RA_EXT_SENS_DATA_13 = 0x56
__MPU6050_RA_EXT_SENS_DATA_14 = 0x57
__MPU6050_RA_EXT_SENS_DATA_15 = 0x58
__MPU6050_RA_EXT_SENS_DATA_16 = 0x59
__MPU6050_RA_EXT_SENS_DATA_17 = 0x5A
__MPU6050_RA_EXT_SENS_DATA_18 = 0x5B
__MPU6050_RA_EXT_SENS_DATA_19 = 0x5C
__MPU6050_RA_EXT_SENS_DATA_20 = 0x5D
__MPU6050_RA_EXT_SENS_DATA_21 = 0x5E
__MPU6050_RA_EXT_SENS_DATA_22 = 0x5F
__MPU6050_RA_EXT_SENS_DATA_23 = 0x60
__MPU6050_RA_MOT_DETECT_STATUS = 0x61
__MPU6050_RA_I2C_SLV0_DO = 0x63
__MPU6050_RA_I2C_SLV1_DO = 0x64
__MPU6050_RA_I2C_SLV2_DO = 0x65
__MPU6050_RA_I2C_SLV3_DO = 0x66
__MPU6050_RA_I2C_MST_DELAY_CTRL = 0x67
__MPU6050_RA_SIGNAL_PATH_RESET = 0x68
__MPU6050_RA_MOT_DETECT_CTRL = 0x69
__MPU6050_RA_USER_CTRL = 0x6A
__MPU6050_RA_PWR_MGMT_1 = 0x6B
__MPU6050_RA_PWR_MGMT_2 = 0x6C
__MPU6050_RA_BANK_SEL = 0x6D
__MPU6050_RA_MEM_START_ADDR = 0x6E
__MPU6050_RA_MEM_R_W = 0x6F
__MPU6050_RA_DMP_CFG_1 = 0x70
__MPU6050_RA_DMP_CFG_2 = 0x71
__MPU6050_RA_FIFO_COUNTH = 0x72
__MPU6050_RA_FIFO_COUNTL = 0x73
__MPU6050_RA_FIFO_R_W = 0x74
__MPU6050_RA_WHO_AM_I = 0x75
#-----------------------------------------------------------------------------------------------
# Compass output registers when using the I2C master / slave
#-----------------------------------------------------------------------------------------------
__MPU9250_RA_MAG_XOUT_L = 0x4A
__MPU9250_RA_MAG_XOUT_H = 0x4B
__MPU9250_RA_MAG_YOUT_L = 0x4C
__MPU9250_RA_MAG_YOUT_H = 0x4D
__MPU9250_RA_MAG_ZOUT_L = 0x4E
__MPU9250_RA_MAG_ZOUT_H = 0x4F
#-----------------------------------------------------------------------------------------------
# Compass output registers when directly accessing via IMU bypass
#-----------------------------------------------------------------------------------------------
__AK893_RA_WIA = 0x00
__AK893_RA_INFO = 0x01
__AK893_RA_ST1 = 0x00
__AK893_RA_X_LO = 0x03
__AK893_RA_X_HI = 0x04
__AK893_RA_Y_LO = 0x05
__AK893_RA_Y_HI = 0x06
__AK893_RA_Z_LO = 0x07
__AK893_RA_Z_HI = 0x08
__AK893_RA_ST2 = 0x09
__AK893_RA_CNTL1 = 0x0A
__AK893_RA_RSV = 0x0B
__AK893_RA_ASTC = 0x0C
__AK893_RA_TS1 = 0x0D
__AK893_RA_TS2 = 0x0E
__AK893_RA_I2CDIS = 0x0F
__AK893_RA_ASAX = 0x10
__AK893_RA_ASAY = 0x11
__AK893_RA_ASAZ = 0x12
__RANGE_ACCEL = 8 #AB: +/- 8g
__RANGE_GYRO = 250 #AB: +/- 250o/s
__SCALE_GYRO = math.radians(2 * __RANGE_GYRO / 65536)
__SCALE_ACCEL = 2 * __RANGE_ACCEL / 65536
def __init__(self, address=0x68, alpf=2, glpf=1):
self.i2c = I2C(address)
self.address = address
self.min_az = 0.0
self.max_az = 0.0
self.min_gx = 0.0
self.max_gx = 0.0
self.min_gy = 0.0
self.max_gy = 0.0
self.min_gz = 0.0
self.max_gz = 0.0
self.ax_offset = 0.0
self.ay_offset = 0.0
self.az_offset = 0.0
self.gx_offset = 0.0
self.gy_offset = 0.0
self.gz_offset = 0.0
logger.info('Reseting MPU-6050')
#-------------------------------------------------------------------------------------------
# Reset all registers
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_PWR_MGMT_1, 0x80)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Sets sample rate to 1kHz/(1+0) = 1kHz or 1ms (note 1kHz assumes dlpf is on - setting
# dlpf to 0 or 7 changes 1kHz to 8kHz and therefore will require sample rate divider
# to be changed to 7 to obtain the same 1kHz sample rate.
#-------------------------------------------------------------------------------------------
sample_rate_divisor = int(round(adc_frequency / sampling_rate))
logger.warning("SRD:, %d", sample_rate_divisor)
self.i2c.write8(self.__MPU6050_RA_SMPLRT_DIV, sample_rate_divisor - 1)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Sets clock source to gyro reference w/ PLL
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_PWR_MGMT_1, 0x01)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Gyro DLPF => 1kHz sample frequency used above divided by the sample divide factor.
#
# 0x00 = 250Hz @ 8kHz sampling - DO NOT USE, THE ACCELEROMETER STILL SAMPLES AT 1kHz WHICH PRODUCES EXPECTED BUT NOT CODED FOR TIMING AND FIFO CONTENT PROBLEMS
# 0x01 = 184Hz
# 0x02 = 92Hz
# 0x03 = 41Hz
# 0x04 = 20Hz
# 0x05 = 10Hz
# 0x06 = 5Hz
# 0x07 = 3600Hz @ 8kHz
#
# 0x0* FIFO overflow overwrites oldest FIFO contents
# 0x4* FIFO overflow does not overwrite full FIFO contents
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_CONFIG, 0x40 | glpf)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Disable gyro self tests, scale of +/- 250 degrees/s
#
# 0x00 = +/- 250 degrees/s
# 0x08 = +/- 500 degrees/s
# 0x10 = +/- 1000 degrees/s
# 0x18 = +/- 2000 degrees/s
# See SCALE_GYRO for conversion from raw data to units of radians per second
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_GYRO_CONFIG, int(round(math.log(self.__RANGE_GYRO / 250, 2))) << 3)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Accel DLPF => 1kHz sample frequency used above divided by the sample divide factor.
#
# 0x00 = 460Hz
# 0x01 = 184Hz
# 0x02 = 92Hz
# 0x03 = 41Hz
# 0x04 = 20Hz
# 0x05 = 10Hz
# 0x06 = 5Hz
# 0x07 = 460Hz
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU9250_RA_ACCEL_CFG_2, alpf)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Disable accel self tests, scale of +/-8g
#
# 0x00 = +/- 2g
# 0x08 = +/- 4g
# 0x10 = +/- 8g
# 0x18 = +/- 16g
# See SCALE_ACCEL for convertion from raw data to units of meters per second squared
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_ACCEL_CONFIG, int(round(math.log(self.__RANGE_ACCEL / 2, 2))) << 3)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Set INT pin to push/pull, latch 'til read, any read to clear
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_INT_PIN_CFG, 0x30)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Initialize the FIFO overflow interrupt 0x10 (turned off at startup).
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_INT_ENABLE, 0x00)
time.sleep(0.1)
#-------------------------------------------------------------------------------------------
# Enabled the FIFO.
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_USER_CTRL, 0x40)
#-------------------------------------------------------------------------------------------
# Accelerometer / gyro goes into FIFO later on - see flushFIFO()
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_FIFO_EN, 0x00)
#-------------------------------------------------------------------------------------------
# Read ambient temperature
#-------------------------------------------------------------------------------------------
temp = self.readTemperature()
logger.critical("IMU core temp (boot): ,%f", temp / 333.86 + 21.0)
def readTemperature(self):
temp = self.i2c.readS16(self.__MPU6050_RA_TEMP_OUT_H)
return temp
def enableFIFOOverflowISR(self):
#-------------------------------------------------------------------------------------------
# Clear the interrupt status register and enable the FIFO overflow interrupt 0x10
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_INT_ENABLE, 0x10)
self.i2c.readU8(self.__MPU6050_RA_INT_STATUS)
def disableFIFOOverflowISR(self):
#-------------------------------------------------------------------------------------------
# Disable the FIFO overflow interrupt.
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_INT_ENABLE, 0x00)
def numFIFOBatches(self):
#-------------------------------------------------------------------------------------------
# The FIFO is 512 bytes long, and we're storing 6 signed shorts (ax, ay, az, gx, gy, gz) i.e.
# 12 bytes per batch of sensor readings
#-------------------------------------------------------------------------------------------
fifo_bytes = self.i2c.readU16(self.__MPU6050_RA_FIFO_COUNTH)
fifo_batches = int(fifo_bytes / 12) # This rounds down
return fifo_batches
def readFIFO(self, fifo_batches):
#-------------------------------------------------------------------------------------------
# Read n x 12 bytes of FIFO data averaging, and return the averaged values and inferred time
# based upon the sampling rate and the number of samples.
#-------------------------------------------------------------------------------------------
ax = 0
ay = 0
az = 0
gx = 0
gy = 0
gz = 0
for ii in range(fifo_batches):
sensor_data = []
fifo_batch = self.i2c.readList(self.__MPU6050_RA_FIFO_R_W, 12)
for jj in range(0, 12, 2):
hibyte = fifo_batch[jj]
hibyte = hibyte - 256 if hibyte > 127 else hibyte
lobyte = fifo_batch[jj + 1]
sensor_data.append((hibyte << 8) + lobyte)
ax += sensor_data[0]
ay += sensor_data[1]
az += sensor_data[2]
gx += sensor_data[3]
gy += sensor_data[4]
gz += sensor_data[5]
'''
self.max_az = self.max_az if sensor_data[2] < self.max_az else sensor_data[2]
self.min_az = self.min_az if sensor_data[2] > self.min_az else sensor_data[2]
self.max_gx = self.max_gx if sensor_data[3] < self.max_gx else sensor_data[3]
self.min_gx = self.min_gx if sensor_data[3] > self.min_gx else sensor_data[3]
self.max_gy = self.max_gy if sensor_data[4] < self.max_gy else sensor_data[4]
self.min_gy = self.min_gy if sensor_data[4] > self.min_gy else sensor_data[4]
self.max_gz = self.max_gz if sensor_data[5] < self.max_gz else sensor_data[5]
self.min_gz = self.min_gz if sensor_data[5] > self.min_gz else sensor_data[5]
'''
return ax / fifo_batches, ay / fifo_batches, az / fifo_batches, gx / fifo_batches, gy / fifo_batches, gz / fifo_batches, fifo_batches / sampling_rate
def flushFIFO(self):
#-------------------------------------------------------------------------------------------
# First shut off the feed in the FIFO.
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_FIFO_EN, 0x00)
#-------------------------------------------------------------------------------------------
# Empty the FIFO by reading whatever is there
#-------------------------------------------------------------------------------------------
SMBUS_MAX_BUF_SIZE = 32
fifo_bytes = self.i2c.readU16(self.__MPU6050_RA_FIFO_COUNTH)
for ii in range(int(fifo_bytes / SMBUS_MAX_BUF_SIZE)):
self.i2c.readList(self.__MPU6050_RA_FIFO_R_W, SMBUS_MAX_BUF_SIZE)
fifo_bytes = self.i2c.readU16(self.__MPU6050_RA_FIFO_COUNTH)
for ii in range(fifo_bytes):
self.i2c.readU8(self.__MPU6050_RA_FIFO_R_W)
#-------------------------------------------------------------------------------------------
# Finally start feeding the FIFO with sensor data again
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__MPU6050_RA_FIFO_EN, 0x78)
def setGyroOffsets(self, gx, gy, gz):
self.gx_offset = gx
self.gy_offset = gy
self.gz_offset = gz
def scaleSensors(self, ax, ay, az, gx, gy, gz):
qax = (ax - self.ax_offset) * self.__SCALE_ACCEL
qay = (ay - self.ay_offset) * self.__SCALE_ACCEL
qaz = (az - self.az_offset) * self.__SCALE_ACCEL
qrx = (gx - self.gx_offset) * self.__SCALE_GYRO
qry = (gy - self.gy_offset) * self.__SCALE_GYRO
qrz = (gz - self.gz_offset) * self.__SCALE_GYRO
return qax, qay, qaz, qrx, qry, qrz
def initCompass(self):
#-------------------------------------------------------------------------------------------
# Set up the I2C master pass through.
#-------------------------------------------------------------------------------------------
int_bypass = self.i2c.readU8(self.__MPU6050_RA_INT_PIN_CFG)
self.i2c.write8(self.__MPU6050_RA_INT_PIN_CFG, int_bypass | 0x02)
#-------------------------------------------------------------------------------------------
# Connect directly to the bypassed magnetometer, and configured it for 16 bit continuous data
#-------------------------------------------------------------------------------------------
self.i2c_compass = I2C(0x0C)
self.i2c_compass.write8(self.__AK893_RA_CNTL1, 0x16);
def readCompass(self):
compass_bytes = self.i2c_compass.readList(self.__AK893_RA_X_LO, 7)
#-------------------------------------------------------------------------------------------
# Convert the array of 6 bytes to 3 shorts - 7th byte kicks off another read.
# Note compass X, Y, Z are aligned with GPS not IMU i.e. X = 0, Y = 1 => 0 degrees North
#-------------------------------------------------------------------------------------------
compass_data = []
for ii in range(0, 6, 2):
lobyte = compass_bytes[ii]
hibyte = compass_bytes[ii + 1]
hibyte = hibyte - 256 if hibyte > 127 else hibyte
compass_data.append((hibyte << 8) + lobyte)
[mgx, mgy, mgz] = compass_data
mgx = (mgx - self.mgx_offset) * self.mgx_gain
mgy = (mgy - self.mgy_offset) * self.mgy_gain
mgz = (mgz - self.mgz_offset) * self.mgz_gain
return mgx, mgy, mgz
def compassCheckCalibrate(self):
rc = True
while True:
coc = raw_input("'check' or 'calibrate'? ")
if coc == "check":
self.checkCompass()
break
elif coc == "calibrate":
rc = self.calibrateCompass()
break
return rc
def checkCompass(self):
print "Pop me on the ground pointing in a known direction based on another compass."
raw_input("Press enter when that's done, and I'll tell you which way I think I'm pointing")
self.loadCompassCalibration()
mgx, mgy, mgz = self.readCompass()
#-------------------------------------------------------------------------------
# Convert compass vector into N, S, E, W variants. Get the compass angle in the
# range of 0 - 359.99.
#-------------------------------------------------------------------------------
compass_angle = (math.degrees(math.atan2(mgx, mgy)) + 360) % 360
#-------------------------------------------------------------------------------
# There are 16 possible compass directions when you include things like NNE at
# 22.5 degrees.
#-------------------------------------------------------------------------------
compass_points = ("N", "NNE", "NE", "ENE", "E", "ESE", "SE", "SSE", "S", "SSW", "SW", "WSW", "W", "WNW", "NW", "NNW")
num_compass_points = len(compass_points)
for ii in range(num_compass_points):
angle_range_min = (360 * (ii - 0.5) / num_compass_points)
angle_range_max = (360 * (ii + 0.5) / num_compass_points)
if compass_angle > angle_range_min and compass_angle <= angle_range_max:
break
else:
ii = 0 # Special case where max < min when north.
print "I think I'm pointing %s?" % compass_points[ii]
def calibrateCompass(self):
self.mgx_offset = 0.0
self.mgy_offset = 0.0
self.mgz_offset = 0.0
self.mgx_gain = 1.0
self.mgy_gain = 1.0
self.mgz_gain = 1.0
offs_rc = False
#-------------------------------------------------------------------------------------------
# First we need gyro offset calibration. Flush the FIFO, collect roughly half a FIFO full
# of samples and feed back to the gyro offset calibrations.
#-------------------------------------------------------------------------------------------
raw_input("First, put me on a stable surface, and press enter.")
mpu6050.flushFIFO()
time.sleep(FULL_FIFO_BATCHES / sampling_rate)
nfb = mpu6050.numFIFOBatches()
qax, qay, qaz, qrx, qry, qrz, dt = mpu6050.readFIFO(nfb)
mpu6050.setGyroOffsets(qrx, qry, qrz)
print "OK, thanks. That's the gyro calibrated."
#-------------------------------------------------------------------------------------------
# Open the offset file for this run
#-------------------------------------------------------------------------------------------
try:
with open('CompassOffsets', 'ab') as offs_file:
mgx, mgy, mgz = self.readCompass()
max_mgx = mgx
min_mgx = mgx
max_mgy = mgy
min_mgy = mgy
max_mgz = mgz
min_mgz = mgz
#-----------------------------------------------------------------------------------
# Collect compass X. Y compass values
#-------------------------------------------------------------------------------
GPIO.output(GPIO_BUZZER, GPIO.LOW)
print "Now, pick me up and rotate me horizontally twice until the buzzing stop."
raw_input("Press enter when you're ready to go.")
self.flushFIFO()
yaw = 0.0
total_dt = 0.0
print "ROTATION: ",
number_len = 0
#-------------------------------------------------------------------------------
# While integrated Z axis gyro < 2 pi i.e. 360 degrees, keep flashing the light
#-------------------------------------------------------------------------------
while abs(yaw) < 4 * math.pi:
time.sleep(10 / sampling_rate)
nfb = mpu6050.numFIFOBatches()
ax, ay, az, gx, gy, gz, dt = self.readFIFO(nfb)
ax, ay, az, gx, gy, gz = self.scaleSensors(ax, ay, az, gx, gy, gz)
yaw += gz * dt
total_dt += dt
mgx, mgy, mgz = self.readCompass()
max_mgx = mgx if mgx > max_mgx else max_mgx
max_mgy = mgy if mgy > max_mgy else max_mgy
min_mgx = mgx if mgx < min_mgx else min_mgx
min_mgy = mgy if mgy < min_mgy else min_mgy
if total_dt > 0.2:
total_dt %= 0.2
number_text = str(abs(int(math.degrees(yaw))))
if len(number_text) == 2:
number_text = " " + number_text
elif len(number_text) == 1:
number_text = " " + number_text
print "\b\b\b\b%s" % number_text,
sys.stdout.flush()
GPIO.output(GPIO_BUZZER, not GPIO.input(GPIO_BUZZER))
print
#-------------------------------------------------------------------------------
# Collect compass Z values
#-------------------------------------------------------------------------------
GPIO.output(GPIO_BUZZER, GPIO.LOW)
print "\nGreat! Now do the same but with my nose down."
raw_input("Press enter when you're ready to go.")
self.flushFIFO()
rotation = 0.0
total_dt = 0.0
print "ROTATION: ",
number_len = 0
#-------------------------------------------------------------------------------
# While integrated X+Y axis gyro < 4 pi i.e. 720 degrees, keep flashing the light
#-------------------------------------------------------------------------------
while abs(rotation) < 4 * math.pi:
time.sleep(10 / sampling_rate)
nfb = self.numFIFOBatches()
ax, ay, az, gx, gy, gz, dt = self.readFIFO(nfb)
ax, ay, az, gx, gy, gz = self.scaleSensors(ax, ay, az, gx, gy, gz)
rotation += math.pow(math.pow(gx, 2) + math.pow(gy, 2), 0.5) * dt
total_dt += dt
mgx, mgy, mgz = self.readCompass()
max_mgz = mgz if mgz > max_mgz else max_mgz
min_mgz = mgz if mgz < min_mgz else min_mgz
if total_dt > 0.2:
total_dt %= 0.2
number_text = str(abs(int(math.degrees(rotation))))
if len(number_text) == 2:
number_text = " " + number_text
elif len(number_text) == 1:
number_text = " " + number_text
print "\b\b\b\b%s" % number_text,
sys.stdout.flush()
GPIO.output(GPIO_BUZZER, not GPIO.input(GPIO_BUZZER))
print
#-------------------------------------------------------------------------------
# Turn the light off regardless of the result
#-------------------------------------------------------------------------------
GPIO.output(GPIO_BUZZER, GPIO.LOW)
#-------------------------------------------------------------------------------
# Write the good output to file.
#-------------------------------------------------------------------------------
mgx_offset = (max_mgx + min_mgx) / 2
mgy_offset = (max_mgy + min_mgy) / 2
mgz_offset = (max_mgz + min_mgz) / 2
mgx_gain = 1 / (max_mgx - min_mgx)
mgy_gain = 1 / (max_mgy - min_mgy)
mgz_gain = 1 / (max_mgz - min_mgz)
offs_file.write("%f %f %f %f %f %f\n" % (mgx_offset, mgy_offset, mgz_offset, mgx_gain, mgy_gain, mgz_gain))
#-------------------------------------------------------------------------------
# Sanity check.
#-------------------------------------------------------------------------------
print "\nLooking good, just one last check to confirm all's well."
self.checkCompass()
print "All done - ready to go!"
offs_rc = True
except EnvironmentError as e:
print "Environment Error: '%s'" % e
return offs_rc
def loadCompassCalibration(self):
self.mgx_offset = 0.0
self.mgy_offset = 0.0
self.mgz_offset = 0.0
self.mgx_gain = 1.0
self.mgy_gain = 1.0
self.mgz_gain = 1.0
offs_rc = False
try:
with open('CompassOffsets', 'rb') as offs_file:
mgx_offset = 0.0
mgy_offset = 0.0
mgz_offset = 0.0
mgx_gain = 1.0
mgy_gain = 1.0
mgz_gain = 1.0
for line in offs_file:
mgx_offset, mgy_offset, mgz_offset, mgx_gain, mgy_gain, mgz_gain = line.split()
self.mgx_offset = float(mgx_offset)
self.mgy_offset = float(mgy_offset)
self.mgz_offset = float(mgz_offset)
self.mgx_gain = float(mgx_gain)
self.mgy_gain = float(mgy_gain)
self.mgz_gain = float(mgz_gain)
except EnvironmentError:
#---------------------------------------------------------------------------------------
# Compass calibration is essential to exclude soft magnetic fields such as from local
# metal; enforce a recalibration if not found.
#---------------------------------------------------------------------------------------
print "Oops, something went wrong reading the compass offsets file 'CompassOffsets'"
print "Have you calibrated it (--cc)?"
offs_rc = False
else:
#---------------------------------------------------------------------------------------
# Calibration results were successful.
#---------------------------------------------------------------------------------------
offs_rc = True
finally:
pass
logger.warning("Compass Offsets:, %f, %f, %f, Compass Gains:, %f, %f, %f", self.mgx_offset,
self.mgy_offset,
self.mgz_offset,
self.mgx_gain,
self.mgy_gain,
self.mgz_gain)
return offs_rc
def calibrate0g(self):
ax_offset = 0.0
ay_offset = 0.0
az_offset = 0.0
offs_rc = False
#-------------------------------------------------------------------------------------------
# Open the ofset file for this run
#-------------------------------------------------------------------------------------------
try:
with open('0gOffsets', 'ab') as offs_file:
raw_input("Rest me on my props and press enter.")
self.flushFIFO()
time.sleep(FULL_FIFO_BATCHES / sampling_rate)
fifo_batches = self.numFIFOBatches()
ax, ay, az, gx, gy, gz, dt = self.readFIFO(fifo_batches)
offs_file.write("%f %f %f\n" % (ax, ay, az))
except EnvironmentError:
pass
else:
offs_rc = True
return offs_rc
def load0gCalibration(self):
offs_rc = False
try:
with open('0gOffsets', 'rb') as offs_file:
for line in offs_file:
ax_offset, ay_offset, az_offset = line.split()
self.ax_offset = float(ax_offset)
self.ay_offset = float(ay_offset)
self.az_offset = float(az_offset)
except EnvironmentError:
pass
else:
pass
finally:
#---------------------------------------------------------------------------------------
# For a while, I thought 0g calibration might help, but actually, it doesn't due to
# temperature dependency, so it always returns default values now.
#---------------------------------------------------------------------------------------
self.ax_offset = 0.0
self.ay_offset = 0.0
self.az_offset = 0.0
offs_rc = True
logger.warning("0g Offsets:, %f, %f, %f", self.ax_offset, self.ay_offset, self.az_offset)
return offs_rc
def getStats(self):
return (self.max_az * self.__SCALE_ACCEL,
self.min_az * self.__SCALE_ACCEL,
self.max_gx * self.__SCALE_GYRO,
self.min_gx * self.__SCALE_GYRO,
self.max_gy * self.__SCALE_GYRO,
self.min_gy * self.__SCALE_GYRO,
self.max_gz * self.__SCALE_GYRO,
self.min_gz * self.__SCALE_GYRO)
####################################################################################################
#
# Garmin LiDAR-Lite v3 range finder
#
####################################################################################################
class GLLv3:
i2c = None
__GLL_ACQ_COMMAND = 0x00
__GLL_STATUS = 0x01
__GLL_SIG_COUNT_VAL = 0x02
__GLL_ACQ_CONFIG_REG = 0x04
__GLL_VELOCITY = 0x09
__GLL_PEAK_CORR = 0x0C
__GLL_NOISE_PEAK = 0x0D
__GLL_SIGNAL_STRENGTH = 0x0E
__GLL_FULL_DELAY_HIGH = 0x0F
__GLL_FULL_DELAY_LOW = 0x10
__GLL_OUTER_LOOP_COUNT = 0x11
__GLL_REF_COUNT_VAL = 0x12
__GLL_LAST_DELAY_HIGH = 0x14
__GLL_LAST_DELAY_LOW = 0x15
__GLL_UNIT_ID_HIGH = 0x16
__GLL_UNIT_ID_LOW = 0x17
__GLL_I2C_ID_HIGHT = 0x18
__GLL_I2C_ID_LOW = 0x19
__GLL_I2C_SEC_ADDR = 0x1A
__GLL_THRESHOLD_BYPASS = 0x1C
__GLL_I2C_CONFIG = 0x1E
__GLL_COMMAND = 0x40
__GLL_MEASURE_DELAY = 0x45
__GLL_PEAK_BCK = 0x4C
__GLL_CORR_DATA = 0x52
__GLL_CORR_DATA_SIGN = 0x53
__GLL_ACQ_SETTINGS = 0x5D
__GLL_POWER_CONTROL = 0x65
def __init__(self, address=0x62, rate=10):
self.i2c = I2C(address)
self.rate = rate
#-------------------------------------------------------------------------------------------
# Set to continuous sampling after initial read.
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__GLL_OUTER_LOOP_COUNT, 0xFF)
#-------------------------------------------------------------------------------------------
# Set the sampling frequency as 2000 / Hz:
# 10Hz = 0xc8
# 20Hz = 0x64
# 100Hz = 0x14
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__GLL_MEASURE_DELAY, int(2000 / rate))
#-------------------------------------------------------------------------------------------
# Include receiver bias correction 0x04
#AB: 0x04 | 0x01 should cause (falling edge?) GPIO_GLL_DR_INTERRUPT. Test GPIO handle this?
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__GLL_ACQ_COMMAND, 0x04 | 0x01)
#-------------------------------------------------------------------------------------------
# Acquisition config register:
# 0x01 Data ready interrupt
# 0x20 Take sampling rate from MEASURE_DELAY
#-------------------------------------------------------------------------------------------
self.i2c.write8(self.__GLL_ACQ_CONFIG_REG, 0x21)
def read(self):
#-------------------------------------------------------------------------------------------
# Distance is in cm hence the 100s to convert to meters.
# Velocity is in cm between consecutive reads; sampling rate converts these to a velocity.
# Reading the list from 0x8F seems to get the previous reading, probably cached for the sake
# of calculating the velocity next time round.
#-------------------------------------------------------------------------------------------
distance = self.i2c.readU16(self.__GLL_FULL_DELAY_HIGH)
if distance == 1:
raise ValueError("GLL out of range")
return distance / 100
####################################################################################################
#
# Garmin LiDAR-Lite v3HP range finder
#
####################################################################################################
class GLLv3HP:
i2c = None
__GLL_ACQ_COMMAND = 0x00
__GLL_STATUS = 0x01
__GLL_SIG_COUNT_VAL = 0x02
__GLL_ACQ_CONFIG_REG = 0x04
__GLL_LEGACY_RESET_EN = 0x06
__GLL_SIGNAL_STRENGTH = 0x0E
__GLL_FULL_DELAY_HIGH = 0x0F
__GLL_FULL_DELAY_LOW = 0x10
__GLL_REF_COUNT_VAL = 0x12
__GLL_UNIT_ID_HIGH = 0x16
__GLL_UNIT_ID_LOW = 0x17
__GLL_I2C_ID_HIGHT = 0x18
__GLL_I2C_ID_LOW = 0x19
__GLL_I2C_SEC_ADDR = 0x1A
__GLL_THRESHOLD_BYPASS = 0x1C
__GLL_I2C_CONFIG = 0x1E
__GLL_PEAK_STACK_HIGH = 0x26
__GLL_PEAK_STACK_LOW = 0x27
__GLL_COMMAND = 0x40
__GLL_HEALTHY_STATUS = 0x48
__GLL_CORR_DATA = 0x52
__GLL_CORR_DATA_SIGN = 0x53
__GLL_POWER_CONTROL = 0x65
def __init__(self, address=0x62):
self.i2c = I2C(address)
self.i2c.write8(self.__GLL_SIG_COUNT_VAL, 0x80)
self.i2c.write8(self.__GLL_ACQ_CONFIG_REG, 0x08)
self.i2c.write8(self.__GLL_REF_COUNT_VAL, 0x05)
self.i2c.write8(self.__GLL_THRESHOLD_BYPASS, 0x00)
def read(self):
acquired = False
# Trigger acquisition
self.i2c.write8(self.__GLL_ACQ_COMMAND, 0x01)
# Poll acquired?
while not acquired:
acquired = not (self.i2c.readU8(self.__GLL_STATUS) & 0x01)
else: