-
Notifications
You must be signed in to change notification settings - Fork 9
/
Copy pathBMX055_MS5637_BasicAHRS_t3.ino
1209 lines (1062 loc) · 55.9 KB
/
BMX055_MS5637_BasicAHRS_t3.ino
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
/* BMX055_MS5637_t3 Basic Example Code
by: Kris Winer
date: August 1, 2014
license: Beerware - Use this code however you'd like. If you
find it useful you can buy me a beer some time.
Demonstrate basic BMX-055 functionality including parameterizing the register addresses, initializing the sensor,
getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to
allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and
Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1.
This sketch is intended specifically for the BMX055+MS5637 Add-on shield for the Teensy 3.1.
It uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h.
The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution
mode but with power consumption od 20 microAmp, or in a lower resolution mode with power consumption of
only 1 microAmp. The choice will depend on the application.
SDA and SCL should have external pull-up resistors (to 3.3V).
4k7 resistors are on the BMX055+MS5637 Mini Add-On board for Teensy 3.1.
Hardware setup:
BMX055 Mini Add-On ------- Teensy 3.1
VDD ---------------------- 3.3V
SDA ----------------------- 17
SCL ----------------------- 16
GND ---------------------- GND
Note: The BMX055 is an I2C sensor and uses the Teensy 3.1 i2c_t3.h Wire library.
Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1.
We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file.
We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file.
*/
//#include "Wire.h"
#include <i2c_t3.h>
#include <SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_PCD8544.h>
// Using NOKIA 5110 monochrome 84 x 48 pixel display
// pin 7 - Serial clock out (SCLK)
// pin 6 - Serial data out (DIN)
// pin 5 - Data/Command select (D/C)
// pin 3 - LCD chip select (SCE)
// pin 4 - LCD reset (RST)
Adafruit_PCD8544 display = Adafruit_PCD8544(7, 6, 5, 3, 4);
// See MS5637-02BA03 Low Voltage Barometric Pressure Sensor Data Sheet http://www.meas-spec.com/downloads/MS5637-02BA03.pdf
#define MS5637_RESET 0x1E
#define NS5637_CONVERT_D1 0x40
#define NS5637_CONVERT_D2 0x50
#define MS5637_ADC_READ 0x00
// BMX055 data sheet http://ae-bst.resource.bosch.com/media/products/dokumente/bmx055/BST-BMX055-DS000-01v2.pdf
// The BMX055 is a conglomeration of three separate motion sensors packaged together but
// addressed and communicated with separately by design
// Accelerometer registers
#define BMX055_ACC_WHOAMI 0x00 // should return 0xFA
//#define BMX055_ACC_Reserved 0x01
#define BMX055_ACC_D_X_LSB 0x02
#define BMX055_ACC_D_X_MSB 0x03
#define BMX055_ACC_D_Y_LSB 0x04
#define BMX055_ACC_D_Y_MSB 0x05
#define BMX055_ACC_D_Z_LSB 0x06
#define BMX055_ACC_D_Z_MSB 0x07
#define BMX055_ACC_D_TEMP 0x08
#define BMX055_ACC_INT_STATUS_0 0x09
#define BMX055_ACC_INT_STATUS_1 0x0A
#define BMX055_ACC_INT_STATUS_2 0x0B
#define BMX055_ACC_INT_STATUS_3 0x0C
//#define BMX055_ACC_Reserved 0x0D
#define BMX055_ACC_FIFO_STATUS 0x0E
#define BMX055_ACC_PMU_RANGE 0x0F
#define BMX055_ACC_PMU_BW 0x10
#define BMX055_ACC_PMU_LPW 0x11
#define BMX055_ACC_PMU_LOW_POWER 0x12
#define BMX055_ACC_D_HBW 0x13
#define BMX055_ACC_BGW_SOFTRESET 0x14
//#define BMX055_ACC_Reserved 0x15
#define BMX055_ACC_INT_EN_0 0x16
#define BMX055_ACC_INT_EN_1 0x17
#define BMX055_ACC_INT_EN_2 0x18
#define BMX055_ACC_INT_MAP_0 0x19
#define BMX055_ACC_INT_MAP_1 0x1A
#define BMX055_ACC_INT_MAP_2 0x1B
//#define BMX055_ACC_Reserved 0x1C
//#define BMX055_ACC_Reserved 0x1D
#define BMX055_ACC_INT_SRC 0x1E
//#define BMX055_ACC_Reserved 0x1F
#define BMX055_ACC_INT_OUT_CTRL 0x20
#define BMX055_ACC_INT_RST_LATCH 0x21
#define BMX055_ACC_INT_0 0x22
#define BMX055_ACC_INT_1 0x23
#define BMX055_ACC_INT_2 0x24
#define BMX055_ACC_INT_3 0x25
#define BMX055_ACC_INT_4 0x26
#define BMX055_ACC_INT_5 0x27
#define BMX055_ACC_INT_6 0x28
#define BMX055_ACC_INT_7 0x29
#define BMX055_ACC_INT_8 0x2A
#define BMX055_ACC_INT_9 0x2B
#define BMX055_ACC_INT_A 0x2C
#define BMX055_ACC_INT_B 0x2D
#define BMX055_ACC_INT_C 0x2E
#define BMX055_ACC_INT_D 0x2F
#define BMX055_ACC_FIFO_CONFIG_0 0x30
//#define BMX055_ACC_Reserved 0x31
#define BMX055_ACC_PMU_SELF_TEST 0x32
#define BMX055_ACC_TRIM_NVM_CTRL 0x33
#define BMX055_ACC_BGW_SPI3_WDT 0x34
//#define BMX055_ACC_Reserved 0x35
#define BMX055_ACC_OFC_CTRL 0x36
#define BMX055_ACC_OFC_SETTING 0x37
#define BMX055_ACC_OFC_OFFSET_X 0x38
#define BMX055_ACC_OFC_OFFSET_Y 0x39
#define BMX055_ACC_OFC_OFFSET_Z 0x3A
#define BMX055_ACC_TRIM_GPO 0x3B
#define BMX055_ACC_TRIM_GP1 0x3C
//#define BMX055_ACC_Reserved 0x3D
#define BMX055_ACC_FIFO_CONFIG_1 0x3E
#define BMX055_ACC_FIFO_DATA 0x3F
// BMX055 Gyroscope Registers
#define BMX055_GYRO_WHOAMI 0x00 // should return 0x0F
//#define BMX055_GYRO_Reserved 0x01
#define BMX055_GYRO_RATE_X_LSB 0x02
#define BMX055_GYRO_RATE_X_MSB 0x03
#define BMX055_GYRO_RATE_Y_LSB 0x04
#define BMX055_GYRO_RATE_Y_MSB 0x05
#define BMX055_GYRO_RATE_Z_LSB 0x06
#define BMX055_GYRO_RATE_Z_MSB 0x07
//#define BMX055_GYRO_Reserved 0x08
#define BMX055_GYRO_INT_STATUS_0 0x09
#define BMX055_GYRO_INT_STATUS_1 0x0A
#define BMX055_GYRO_INT_STATUS_2 0x0B
#define BMX055_GYRO_INT_STATUS_3 0x0C
//#define BMX055_GYRO_Reserved 0x0D
#define BMX055_GYRO_FIFO_STATUS 0x0E
#define BMX055_GYRO_RANGE 0x0F
#define BMX055_GYRO_BW 0x10
#define BMX055_GYRO_LPM1 0x11
#define BMX055_GYRO_LPM2 0x12
#define BMX055_GYRO_RATE_HBW 0x13
#define BMX055_GYRO_BGW_SOFTRESET 0x14
#define BMX055_GYRO_INT_EN_0 0x15
#define BMX055_GYRO_INT_EN_1 0x16
#define BMX055_GYRO_INT_MAP_0 0x17
#define BMX055_GYRO_INT_MAP_1 0x18
#define BMX055_GYRO_INT_MAP_2 0x19
#define BMX055_GYRO_INT_SRC_1 0x1A
#define BMX055_GYRO_INT_SRC_2 0x1B
#define BMX055_GYRO_INT_SRC_3 0x1C
//#define BMX055_GYRO_Reserved 0x1D
#define BMX055_GYRO_FIFO_EN 0x1E
//#define BMX055_GYRO_Reserved 0x1F
//#define BMX055_GYRO_Reserved 0x20
#define BMX055_GYRO_INT_RST_LATCH 0x21
#define BMX055_GYRO_HIGH_TH_X 0x22
#define BMX055_GYRO_HIGH_DUR_X 0x23
#define BMX055_GYRO_HIGH_TH_Y 0x24
#define BMX055_GYRO_HIGH_DUR_Y 0x25
#define BMX055_GYRO_HIGH_TH_Z 0x26
#define BMX055_GYRO_HIGH_DUR_Z 0x27
//#define BMX055_GYRO_Reserved 0x28
//#define BMX055_GYRO_Reserved 0x29
//#define BMX055_GYRO_Reserved 0x2A
#define BMX055_GYRO_SOC 0x31
#define BMX055_GYRO_A_FOC 0x32
#define BMX055_GYRO_TRIM_NVM_CTRL 0x33
#define BMX055_GYRO_BGW_SPI3_WDT 0x34
//#define BMX055_GYRO_Reserved 0x35
#define BMX055_GYRO_OFC1 0x36
#define BMX055_GYRO_OFC2 0x37
#define BMX055_GYRO_OFC3 0x38
#define BMX055_GYRO_OFC4 0x39
#define BMX055_GYRO_TRIM_GP0 0x3A
#define BMX055_GYRO_TRIM_GP1 0x3B
#define BMX055_GYRO_BIST 0x3C
#define BMX055_GYRO_FIFO_CONFIG_0 0x3D
#define BMX055_GYRO_FIFO_CONFIG_1 0x3E
// BMX055 magnetometer registers
#define BMX055_MAG_WHOAMI 0x40 // should return 0x32
#define BMX055_MAG_Reserved 0x41
#define BMX055_MAG_XOUT_LSB 0x42
#define BMX055_MAG_XOUT_MSB 0x43
#define BMX055_MAG_YOUT_LSB 0x44
#define BMX055_MAG_YOUT_MSB 0x45
#define BMX055_MAG_ZOUT_LSB 0x46
#define BMX055_MAG_ZOUT_MSB 0x47
#define BMX055_MAG_ROUT_LSB 0x48
#define BMX055_MAG_ROUT_MSB 0x49
#define BMX055_MAG_INT_STATUS 0x4A
#define BMX055_MAG_PWR_CNTL1 0x4B
#define BMX055_MAG_PWR_CNTL2 0x4C
#define BMX055_MAG_INT_EN_1 0x4D
#define BMX055_MAG_INT_EN_2 0x4E
#define BMX055_MAG_LOW_THS 0x4F
#define BMX055_MAG_HIGH_THS 0x50
#define BMX055_MAG_REP_XY 0x51
#define BMX055_MAG_REP_Z 0x52
/* Trim Extended Registers */
#define BMM050_DIG_X1 0x5D // needed for magnetic field calculation
#define BMM050_DIG_Y1 0x5E
#define BMM050_DIG_Z4_LSB 0x62
#define BMM050_DIG_Z4_MSB 0x63
#define BMM050_DIG_X2 0x64
#define BMM050_DIG_Y2 0x65
#define BMM050_DIG_Z2_LSB 0x68
#define BMM050_DIG_Z2_MSB 0x69
#define BMM050_DIG_Z1_LSB 0x6A
#define BMM050_DIG_Z1_MSB 0x6B
#define BMM050_DIG_XYZ1_LSB 0x6C
#define BMM050_DIG_XYZ1_MSB 0x6D
#define BMM050_DIG_Z3_LSB 0x6E
#define BMM050_DIG_Z3_MSB 0x6F
#define BMM050_DIG_XY2 0x70
#define BMM050_DIG_XY1 0x71
// Using the Teensy Mini Add-On board, SDO1 = SDO2 = CSB3 = GND as designed
// Seven-bit device addresses are ACC = 0x18, GYRO = 0x68, MAG = 0x10
#define BMX055_ACC_ADDRESS 0x18 // Address of BMX055 accelerometer
#define BMX055_GYRO_ADDRESS 0x68 // Address of BMX055 gyroscope
#define BMX055_MAG_ADDRESS 0x10 // Address of BMX055 magnetometer
#define MS5637_ADDRESS 0x76 // Address of altimeter
#define SerialDebug true // set to true to get Serial output for debugging
// Set initial input parameters
// define X055 ACC full scale options
#define AFS_2G 0x03
#define AFS_4G 0x05
#define AFS_8G 0x08
#define AFS_16G 0x0C
enum ACCBW { // define BMX055 accelerometer bandwidths
ABW_8Hz, // 7.81 Hz, 64 ms update time
ABW_16Hz, // 15.63 Hz, 32 ms update time
ABW_31Hz, // 31.25 Hz, 16 ms update time
ABW_63Hz, // 62.5 Hz, 8 ms update time
ABW_125Hz, // 125 Hz, 4 ms update time
ABW_250Hz, // 250 Hz, 2 ms update time
ABW_500Hz, // 500 Hz, 1 ms update time
ABW_100Hz // 1000 Hz, 0.5 ms update time
};
enum Gscale {
GFS_2000DPS = 0,
GFS_1000DPS,
GFS_500DPS,
GFS_250DPS,
GFS_125DPS
};
enum GODRBW {
G_2000Hz523Hz = 0, // 2000 Hz ODR and unfiltered (bandwidth 523Hz)
G_2000Hz230Hz,
G_1000Hz116Hz,
G_400Hz47Hz,
G_200Hz23Hz,
G_100Hz12Hz,
G_200Hz64Hz,
G_100Hz32Hz // 100 Hz ODR and 32 Hz bandwidth
};
enum MODR {
MODR_10Hz = 0, // 10 Hz ODR
MODR_2Hz , // 2 Hz ODR
MODR_6Hz , // 6 Hz ODR
MODR_8Hz , // 8 Hz ODR
MODR_15Hz , // 15 Hz ODR
MODR_20Hz , // 20 Hz ODR
MODR_25Hz , // 25 Hz ODR
MODR_30Hz // 30 Hz ODR
};
enum Mmode {
lowPower = 0, // rms noise ~1.0 microTesla, 0.17 mA power
Regular , // rms noise ~0.6 microTesla, 0.5 mA power
enhancedRegular , // rms noise ~0.5 microTesla, 0.8 mA power
highAccuracy // rms noise ~0.3 microTesla, 4.9 mA power
};
// MS5637 pressure sensor sample rates
#define ADC_256 0x00 // define pressure and temperature conversion rates
#define ADC_512 0x02
#define ADC_1024 0x04
#define ADC_2048 0x06
#define ADC_4096 0x08
#define ADC_8192 0x0A
#define ADC_D1 0x40
#define ADC_D2 0x50
// Specify sensor full scale
uint8_t OSR = ADC_8192; // set pressure amd temperature oversample rate
uint8_t Gscale = GFS_125DPS; // set gyro full scale
uint8_t GODRBW = G_200Hz23Hz; // set gyro ODR and bandwidth
uint8_t Ascale = AFS_2G; // set accel full scale
uint8_t ACCBW = 0x08 | ABW_16Hz; // Choose bandwidth for accelerometer, need bit 3 = 1 to enable bandwidth choice in enum
uint8_t Mmode = Regular; // Choose magnetometer operation mode
uint8_t MODR = MODR_10Hz; // set magnetometer data rate
float aRes, gRes, mRes; // scale resolutions per LSB for the sensors
// Parameters to hold BMX055 trim values
signed char dig_x1;
signed char dig_y1;
signed char dig_x2;
signed char dig_y2;
uint16_t dig_z1;
int16_t dig_z2;
int16_t dig_z3;
int16_t dig_z4;
unsigned char dig_xy1;
signed char dig_xy2;
uint16_t dig_xyz1;
// Pin definitions
// The BMX055 has three sensors, and two interrupt pins per device!
int intACC1 = 8; // These are fixed on the BMX055 Mini Add-On for Teensy 3.1
int intACC2 = 9;
int intGYRO1 = 11;
int intGYRO2 = 10;
int intMAG1 = 12;
int intDRDYM = 15;
int myLed = 13; // LED on the Teensy 3.1
// MS5637 variables
uint16_t Pcal[8]; // calibration constants from MS5637 PROM registers
unsigned char nCRC; // calculated check sum to ensure PROM integrity
uint32_t D1 = 0, D2 = 0; // raw MS5637 pressure and temperature data
double dT, OFFSET, SENS, T2, OFFSET2, SENS2; // First order and second order corrections for raw S5637 temperature and pressure data
double Temperature, Pressure; // stores MS5637 pressures sensor pressure and temperature
// BMX055 variables
int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
int16_t magCount[3]; // Stores the 13/15-bit signed magnetometer sensor output
float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}; // Bias corrections for gyro, accelerometer, mag
int16_t tempCount; // temperature raw count output
float temperature; // Stores the BMX055 internal chip temperature in degrees Celsius
float SelfTest[6]; // holds results of gyro and accelerometer self test
// global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System)
float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s)
float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
// There is a tradeoff in the beta parameter between accuracy and response speed.
// In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy.
// However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion.
// Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car!
// By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec
// I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense;
// the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy.
// In any case, this is the free parameter in the Madgwick filtering and fusion scheme.
float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value
#define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral
#define Ki 0.0f
uint32_t delt_t = 0, count = 0, sumCount = 0; // used to control display output rate
float pitch, yaw, roll;
float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes
uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval
uint32_t Now = 0; // used to calculate integration interval
float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
void setup()
{
// Wire.begin();
// TWBR = 12; // 400 kbit/sec I2C speed for Pro Mini
// Setup for Master mode, pins 18/19, external pullups, 400kHz for Teensy 3.1
Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_400);
delay(5000);
Serial.begin(38400);
// Set up the interrupt pin, its set as active high, push-pull
pinMode(intACC1, INPUT);
pinMode(intACC2, INPUT);
pinMode(intGYRO1, INPUT);
pinMode(intGYRO2, INPUT);
pinMode(intMAG1, INPUT);
pinMode(intDRDYM, INPUT);
pinMode(myLed, OUTPUT);
digitalWrite(myLed, HIGH);
display.begin(); // Initialize the display
display.setContrast(58); // Set the contrast
// Start device display with ID of sensor
display.clearDisplay();
display.setTextSize(2);
display.setCursor(0,0); display.print("BMX055");
display.setTextSize(1);
display.setCursor(0, 20); display.print("9-DOF 16-bit");
display.setCursor(0, 30); display.print("motion sensor");
display.setCursor(20,40); display.print("1 mg LSB");
display.display();
delay(1000);
// Set up for data display
display.setTextSize(1); // Set text size to normal, 2 is twice normal etc.
display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen
display.clearDisplay(); // clears the screen and buffer
// Read the BMX-055 WHO_AM_I registers, this is a good test of communication
Serial.println("BMX055 accelerometer...");
byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_WHOAMI); // Read ACC WHO_AM_I register for BMX055
Serial.print("BMX055 ACC"); Serial.print(" I AM 0x"); Serial.print(c, HEX); Serial.print(" I should be 0x"); Serial.println(0xFA, HEX);
display.setCursor(20,0); display.print("BMX055 ACC");
display.setCursor(0,10); display.print("I AM");
display.setCursor(0,20); display.print("0x"); display.print(c, HEX);
display.setCursor(0,30); display.print("I Should Be");
display.setCursor(0,40); display.print("0x"); display.print(0xFA, HEX);
display.display();
delay(1000);
display.clearDisplay(); // clears the screen and buffer
Serial.println("BMX055 gyroscope...");
byte d = readByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_WHOAMI); // Read GYRO WHO_AM_I register for BMX055
Serial.print("BMX055 GYRO"); Serial.print(" I AM 0x"); Serial.print(d, HEX); Serial.print(" I should be 0x"); Serial.println(0x0F, HEX);
display.setCursor(0, 0); display.print("BMX055 GYRO");
display.setCursor(0,10); display.print("I AM");
display.setCursor(0,20); display.print("0x"); display.print(d, HEX);
display.setCursor(0,30); display.print("I Should Be");
display.setCursor(0,40); display.print("0x"); display.print(0x0F, HEX);
display.display();
delay(1000);
Serial.println("BMX055 magnetometer...");
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // wake up magnetometer first thing
delay(100);
byte e = readByte(BMX055_MAG_ADDRESS, BMX055_MAG_WHOAMI); // Read MAG WHO_AM_I register for BMX055
Serial.print("BMX055 MAG"); Serial.print(" I AM 0x"); Serial.print(e, HEX); Serial.print(" I should be 0x"); Serial.println(0x32, HEX);
display.clearDisplay(); // clears the screen and buffer
display.setCursor(0, 0); display.print("BMX055 MAG");
display.setCursor(0,10); display.print("I AM");
display.setCursor(0,20); display.print("0x"); display.print(e, HEX);
display.setCursor(0,30); display.print("I Should Be");
display.setCursor(0,40); display.print("0x"); display.print(0x32, HEX);
display.display();
delay(1000);
if ((c == 0xFA) && (d == 0x0F) && (e == 0x32)) // WHO_AM_I should always be ACC = 0xFA, GYRO = 0x0F, MAG = 0x32
{
Serial.println("BMX055 is online...");
display.clearDisplay(); // clears the screen and buffer
display.setCursor(0, 0); display.print("BMX055 online");
display.setCursor(0,10); display.print("configuring");
display.display();
delay(1000);
initBMX055();
Serial.println("BMX055 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
display.clearDisplay(); // clears the screen and buffer
display.setCursor(0, 0); display.print("BMX055 online");
display.setCursor(0,10); display.print("initialized");
display.display();
delay(1000);
// Reset the MS5637 pressure sensor
MS5637Reset();
delay(100);
Serial.println("MS5637 pressure sensor reset...");
// Read PROM data from MS5637 pressure sensor
MS5637PromRead(Pcal);
Serial.println("PROM dta read:");
Serial.print("C0 = "); Serial.println(Pcal[0]);
unsigned char refCRC = Pcal[0] >> 12;
Serial.print("C1 = "); Serial.println(Pcal[1]);
Serial.print("C2 = "); Serial.println(Pcal[2]);
Serial.print("C3 = "); Serial.println(Pcal[3]);
Serial.print("C4 = "); Serial.println(Pcal[4]);
Serial.print("C5 = "); Serial.println(Pcal[5]);
Serial.print("C6 = "); Serial.println(Pcal[6]);
nCRC = MS5637checkCRC(Pcal); //calculate checksum to ensure integrity of MS5637 calibration data
Serial.print("Checksum = "); Serial.print(nCRC); Serial.print(" , should be "); Serial.println(refCRC);
display.clearDisplay();
display.setCursor(20,0); display.print("MS5637");
display.setCursor(0,10); display.print("CRC is "); display.setCursor(50,10); display.print(nCRC);
display.setCursor(0,20); display.print("Should be "); display.setCursor(50,30); display.print(refCRC);
display.display();
delay(1000);
// get sensor resolutions, only need to do this once
getAres();
getGres();
// magnetometer resolution is 1 microTesla/16 counts or 1/1.6 milliGauss/count
mRes = 1./1.6;
trimBMX055(); // read the magnetometer calibration data
display.clearDisplay();
display.setCursor(0, 0); display.print("BMX055 Res");
display.setCursor(0,10); display.print("ACC "); display.setCursor(50,10); display.print(1000.*aRes, 2);
display.setCursor(0,20); display.print("GYRO "); display.setCursor(50,20); display.print(1000.*gRes, 2);
// display.setCursor(0,30); display.print("MAG "); display.setCursor(50,30); display.print((int)dig_x1);
display.display();
delay(1000);
fastcompaccelBMX055(accelBias);
Serial.println("accel biases (mg)"); Serial.println(1000.*accelBias[0]); Serial.println(1000.*accelBias[1]); Serial.println(1000.*accelBias[2]);
Serial.println("gyro biases (dps)"); Serial.println(gyroBias[0]); Serial.println(gyroBias[1]); Serial.println(gyroBias[2]);
magcalBMX055(magBias);
Serial.println("mag biases (mG)"); Serial.println(magBias[0]); Serial.println(magBias[1]); Serial.println(magBias[2]);
}
else
{
Serial.print("Could not connect to BMX055: 0x");
Serial.println(c, HEX);
while(1) ; // Loop forever if communication doesn't happen
}
}
void loop()
{
// If intPin goes high, all data registers have new data
// if (digitalRead(intACC2)) { // On interrupt, read data
readAccelData(accelCount); // Read the x/y/z adc values
// Now we'll calculate the accleration value into actual g's
ax = (float)accelCount[0]*aRes; // + accelBias[0]; // get actual g value, this depends on scale being set
ay = (float)accelCount[1]*aRes; // + accelBias[1];
az = (float)accelCount[2]*aRes; // + accelBias[2];
// }
// if (digitalRead(intGYRO2)) { // On interrupt, read data
readGyroData(gyroCount); // Read the x/y/z adc values
// Calculate the gyro value into actual degrees per second
gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set
gy = (float)gyroCount[1]*gRes;
gz = (float)gyroCount[2]*gRes;
// }
// if (digitalRead(intDRDYM)) { // On interrupt, read data
readMagData(magCount); // Read the x/y/z adc values
// Calculate the magnetometer values in milliGauss
// Temperature-compensated magnetic field is in 16 LSB/microTesla
mx = (float)magCount[0]*mRes - magBias[0]; // get actual magnetometer value, this depends on scale being set
my = (float)magCount[1]*mRes - magBias[1];
mz = (float)magCount[2]*mRes - magBias[2];
//}
Now = micros();
deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update
lastUpdate = Now;
sum += deltat; // sum for averaging filter update rate
sumCount++;
// Sensors x (y)-axis of the accelerometer is aligned with the -y (x)-axis of the magnetometer;
// the magnetometer z-axis (+ up) is aligned with z-axis (+ up) of accelerometer and gyro!
// We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter.
// For the BMX-055, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like
// in the MPU9250 sensor. This rotation can be modified to allow any convenient orientation convention.
// This is ok by aircraft orientation standards!
// Pass gyro rate as rad/s
MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz);
// MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, mx, mz);
// Serial print and/or display at 0.5 s rate independent of data rates
delt_t = millis() - count;
if (delt_t > 500) { // update LCD once per half-second independent of read rate
if(SerialDebug) {
Serial.print("ax = "); Serial.print((int)1000*ax);
Serial.print(" ay = "); Serial.print((int)1000*ay);
Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg");
Serial.print("gx = "); Serial.print( gx, 2);
Serial.print(" gy = "); Serial.print( gy, 2);
Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s");
Serial.print("mx = "); Serial.print( (int)mx);
Serial.print(" my = "); Serial.print( (int)my);
Serial.print(" mz = "); Serial.print( (int)mz); Serial.println(" mG");
Serial.print("q0 = "); Serial.print(q[0]);
Serial.print(" qx = "); Serial.print(q[1]);
Serial.print(" qy = "); Serial.print(q[2]);
Serial.print(" qz = "); Serial.println(q[3]);
}
// tempCount = readTempData(); // Read the gyro adc values
// temperature = ((float) tempCount) / 333.87 + 21.0; // Gyro chip temperature in degrees Centigrade
// Print temperature in degrees Centigrade
// Serial.print("Gyro temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C
D1 = MS5637Read(ADC_D1, OSR); // get raw pressure value
D2 = MS5637Read(ADC_D2, OSR); // get raw temperature value
dT = D2 - Pcal[5]*pow(2,8); // calculate temperature difference from reference
OFFSET = Pcal[2]*pow(2, 17) + dT*Pcal[4]/pow(2,6);
SENS = Pcal[1]*pow(2,16) + dT*Pcal[3]/pow(2,7);
Temperature = (2000 + (dT*Pcal[6])/pow(2, 23))/100; // First-order Temperature in degrees Centigrade
//
// Second order corrections
if(Temperature > 20)
{
T2 = 5*dT*dT/pow(2, 38); // correction for high temperatures
OFFSET2 = 0;
SENS2 = 0;
}
if(Temperature < 20) // correction for low temperature
{
T2 = 3*dT*dT/pow(2, 33);
OFFSET2 = 61*(100*Temperature - 2000)*(100*Temperature - 2000)/16;
SENS2 = 29*(100*Temperature - 2000)*(100*Temperature - 2000)/16;
}
if(Temperature < -15) // correction for very low temperature
{
OFFSET2 = OFFSET2 + 17*(100*Temperature + 1500)*(100*Temperature + 1500);
SENS2 = SENS2 + 9*(100*Temperature + 1500)*(100*Temperature + 1500);
}
// End of second order corrections
//
Temperature = Temperature - T2/100;
OFFSET = OFFSET - OFFSET2;
SENS = SENS - SENS2;
Pressure = (((D1*SENS)/pow(2, 21) - OFFSET)/pow(2, 15))/100; // Pressure in mbar or kPa
float altitude = 145366.45*(1. - pow((Pressure/1013.25), 0.190284));
if(SerialDebug) {
Serial.print("Digital temperature value = "); Serial.print( (float)Temperature, 2); Serial.println(" C"); // temperature in degrees Celsius
Serial.print("Digital temperature value = "); Serial.print(9.*(float) Temperature/5. + 32., 2); Serial.println(" F"); // temperature in degrees Fahrenheit
Serial.print("Digital pressure value = "); Serial.print((float) Pressure, 2); Serial.println(" mbar");// pressure in millibar
Serial.print("Altitude = "); Serial.print(altitude, 2); Serial.println(" feet");
}
// Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation.
// In this coordinate system, the positive z-axis is down toward Earth.
// Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise.
// Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative.
// Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll.
// These arise from the definition of the homogeneous rotation matrix constructed from quaternions.
// Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be
// applied in the correct order which for this configuration is yaw, pitch, and then roll.
// For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links.
yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]);
pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]);
pitch *= 180.0f / PI;
yaw *= 180.0f / PI;
yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04
roll *= 180.0f / PI;
// Or define output variable according to the Android system, where heading (0 to 260) is defined by the angle between the y-axis
// and True North, pitch is rotation about the x-axis (-180 to +180), and roll is rotation about the y-axis (-90 to +90)
// In this systen, the z-axis is pointing away from Earth, the +y-axis is at the "top" of the device (cellphone) and the +x-axis
// points toward the right of the device.
//
if(SerialDebug) {
Serial.print("Yaw, Pitch, Roll: ");
Serial.print(yaw, 2);
Serial.print(", ");
Serial.print(pitch, 2);
Serial.print(", ");
Serial.println(roll, 2);
Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz");
}
display.clearDisplay();
display.setCursor(0, 0); display.print(" x y z ");
display.setCursor(0, 8); display.print((int)(1000*ax));
display.setCursor(24, 8); display.print((int)(1000*ay));
display.setCursor(48, 8); display.print((int)(1000*az));
display.setCursor(72, 8); display.print("mg");
tempCount = readACCTempData(); // Read the gyro adc values
temperature = ((float) tempCount) / 2.0 + 23.0; // Gyro chip temperature in degrees Centigrade
display.setCursor(64, 0); display.print(9.*temperature/5. + 32., 0); display.print("F");
display.setCursor(0, 16); display.print((int)(gx));
display.setCursor(24, 16); display.print((int)(gy));
display.setCursor(48, 16); display.print((int)(gz));
display.setCursor(66, 16); display.print("o/s");
display.setCursor(0, 24); display.print((int)(mx));
display.setCursor(24, 24); display.print((int)(my));
display.setCursor(48, 24); display.print((int)(mz));
display.setCursor(72, 24); display.print("mG");
display.setCursor(0, 32); display.print((int)(yaw));
display.setCursor(24, 32); display.print((int)(pitch));
display.setCursor(48, 32); display.print((int)(roll));
display.setCursor(66, 32); display.print("ypr");
// With these settings the filter is updating at a ~145 Hz rate using the Madgwick scheme and
// >200 Hz using the Mahony scheme even though the display refreshes at only 2 Hz.
// The filter update rate is determined mostly by the mathematical steps in the respective algorithms,
// the processor speed (8 MHz for the 3.3V Pro Mini), and the magnetometer ODR:
// an ODR of 10 Hz for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces
// filter update rates of 36 - 145 and ~38 Hz for the Madgwick and Mahony schemes, respectively.
// This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads.
// This filter update rate should be fast enough to maintain accurate platform orientation for
// stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz
// produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors.
// The 3.3 V 8 MHz Pro Mini is doing pretty well!
// display.setCursor(0, 40); display.print(altitude, 0); display.print("ft");
// display.setCursor(68, 0); display.print(9.*Temperature/5. + 32., 0);
display.setCursor(42, 40); display.print((float) sumCount / (1000.*sum), 2); display.print("kHz");
display.display();
digitalWrite(myLed, !digitalRead(myLed));
count = millis();
sumCount = 0;
sum = 0;
}
}
//===================================================================================================================
//====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data
//===================================================================================================================
void getGres() {
switch (Gscale)
{
// Possible gyro scales (and their register bit settings) are:
// 125 DPS (100), 250 DPS (011), 500 DPS (010), 1000 DPS (001), and 2000 DPS (000).
case GFS_125DPS:
gRes = 124.87/32768.0; // per data sheet, not exactly 125!?
break;
case GFS_250DPS:
gRes = 249.75/32768.0;
break;
case GFS_500DPS:
gRes = 499.5/32768.0;
break;
case GFS_1000DPS:
gRes = 999.0/32768.0;
break;
case GFS_2000DPS:
gRes = 1998.0/32768.0;
break;
}
}
void getAres() {
switch (Ascale)
{
// Possible accelerometer scales (and their register bit settings) are:
// 2 Gs (0011), 4 Gs (0101), 8 Gs (1000), and 16 Gs (1100).
// BMX055 ACC data is signed 12 bit
case AFS_2G:
aRes = 2.0/2048.0;
break;
case AFS_4G:
aRes = 4.0/2048.0;
break;
case AFS_8G:
aRes = 8.0/2048.0;
break;
case AFS_16G:
aRes = 16.0/2048.0;
break;
}
}
void readAccelData(int16_t * destination)
{
uint8_t rawData[6]; // x/y/z accel register data stored here
readBytes(BMX055_ACC_ADDRESS, BMX055_ACC_D_X_LSB, 6, &rawData[0]); // Read the six raw data registers into data array
if((rawData[0] & 0x01) && (rawData[2] & 0x01) && (rawData[4] & 0x01)) { // Check that all 3 axes have new data
destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 4; // Turn the MSB and LSB into a signed 12-bit value
destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 4;
destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 4;
}
}
void readGyroData(int16_t * destination)
{
uint8_t rawData[6]; // x/y/z gyro register data stored here
readBytes(BMX055_GYRO_ADDRESS, BMX055_GYRO_RATE_X_LSB, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
destination[0] = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value
destination[1] = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]);
destination[2] = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]);
}
void readMagData(int16_t * magData)
{
int16_t mdata_x = 0, mdata_y = 0, mdata_z = 0, temp = 0;
uint16_t data_r = 0;
uint8_t rawData[8]; // x/y/z hall magnetic field data, and Hall resistance data
readBytes(BMX055_MAG_ADDRESS, BMX055_MAG_XOUT_LSB, 8, &rawData[0]); // Read the eight raw data registers sequentially into data array
if(rawData[6] & 0x01) { // Check if data ready status bit is set
mdata_x = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]) >> 3; // 13-bit signed integer for x-axis field
mdata_y = (int16_t) (((int16_t)rawData[3] << 8) | rawData[2]) >> 3; // 13-bit signed integer for y-axis field
mdata_z = (int16_t) (((int16_t)rawData[5] << 8) | rawData[4]) >> 1; // 15-bit signed integer for z-axis field
data_r = (uint16_t) (((uint16_t)rawData[7] << 8) | rawData[6]) >> 2; // 14-bit unsigned integer for Hall resistance
// calculate temperature compensated 16-bit magnetic fields
temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000)));
magData[0] = ((int16_t)((((int32_t)mdata_x) *
((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) +
(((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) +
((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_x2) + ((int16_t)0xA0)))) >> 12)) >> 13)) +
(((int16_t)dig_x1) << 3);
temp = ((int16_t)(((uint16_t)((((int32_t)dig_xyz1) << 14)/(data_r != 0 ? data_r : dig_xyz1))) - ((uint16_t)0x4000)));
magData[1] = ((int16_t)((((int32_t)mdata_y) *
((((((((int32_t)dig_xy2) * ((((int32_t)temp) * ((int32_t)temp)) >> 7)) +
(((int32_t)temp) * ((int32_t)(((int16_t)dig_xy1) << 7)))) >> 9) +
((int32_t)0x100000)) * ((int32_t)(((int16_t)dig_y2) + ((int16_t)0xA0)))) >> 12)) >> 13)) +
(((int16_t)dig_y1) << 3);
magData[2] = (((((int32_t)(mdata_z - dig_z4)) << 15) - ((((int32_t)dig_z3) * ((int32_t)(((int16_t)data_r) -
((int16_t)dig_xyz1))))>>2))/(dig_z2 + ((int16_t)(((((int32_t)dig_z1) * ((((int16_t)data_r) << 1)))+(1<<15))>>16))));
}
}
int16_t readACCTempData()
{
uint8_t c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_TEMP); // Read the raw data register
return ((int16_t)((int16_t)c << 8)) >> 8 ; // Turn the byte into a signed 8-bit integer
}
void trimBMX055() // get trim values for magnetometer sensitivity
{
uint8_t rawData[2]; //placeholder for 2-byte trim data
dig_x1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X1);
dig_x2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_X2);
dig_y1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y1);
dig_y2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_Y2);
dig_xy1 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY1);
dig_xy2 = readByte(BMX055_ACC_ADDRESS, BMM050_DIG_XY2);
readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z1_LSB, 2, &rawData[0]);
dig_z1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]);
readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z2_LSB, 2, &rawData[0]);
dig_z2 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]);
readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z3_LSB, 2, &rawData[0]);
dig_z3 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]);
readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_Z4_LSB, 2, &rawData[0]);
dig_z4 = (int16_t) (((int16_t)rawData[1] << 8) | rawData[0]);
readBytes(BMX055_MAG_ADDRESS, BMM050_DIG_XYZ1_LSB, 2, &rawData[0]);
dig_xyz1 = (uint16_t) (((uint16_t)rawData[1] << 8) | rawData[0]);
}
void initBMX055()
{
// start with all sensors in default mode with all registers reset
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SOFTRESET, 0xB6); // reset accelerometer
delay(1000); // Wait for all registers to reset
// Configure accelerometer
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_RANGE, Ascale & 0x0F); // Set accelerometer full range
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_PMU_BW, ACCBW & 0x0F); // Set accelerometer bandwidth
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_D_HBW, 0x00); // Use filtered data
// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_EN_1, 0x10); // Enable ACC data ready interrupt
// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_OUT_CTRL, 0x04); // Set interrupts push-pull, active high for INT1 and INT2
// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x02); // Define INT1 (intACC1) as ACC data ready interrupt
// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_INT_MAP_1, 0x80); // Define INT2 (intACC2) as ACC data ready interrupt
// writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_BGW_SPI3_WDT, 0x06); // Set watchdog timer for 50 ms
// Configure Gyro
// start by resetting gyro, better not since it ends up in sleep mode?!
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SOFTRESET, 0xB6); // reset gyro
// delay(100);
// Three power modes, 0x00 Normal,
// set bit 7 to 1 for suspend mode, set bit 5 to 1 for deep suspend mode
// sleep duration in fast-power up from suspend mode is set by bits 1 - 3
// 000 for 2 ms, 111 for 20 ms, etc.
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM1, 0x00); // set GYRO normal mode
// set GYRO sleep duration for fast power-up mode to 20 ms, for duty cycle of 50%
// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM1, 0x0E);
// set bit 7 to 1 for fast-power-up mode, gyro goes quickly to normal mode upon wake up
// can set external wake-up interrupts on bits 5 and 4
// auto-sleep wake duration set in bits 2-0, 001 4 ms, 111 40 ms
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_LPM2, 0x00); // set GYRO normal mode
// set gyro to fast wake up mode, will sleep for 20 ms then run normally for 20 ms
// and collect data for an effective ODR of 50 Hz, other duty cycles are possible but there
// is a minimum wake duration determined by the bandwidth duration, e.g., > 10 ms for 23Hz gyro bandwidth
// writeByte(BMX055_ACC_ADDRESS, BMX055_GYRO_LPM2, 0x87);
writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_RANGE, Gscale); // set GYRO FS range
writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BW, GODRBW); // set GYRO ODR and Bandwidth
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_0, 0x80); // enable data ready interrupt
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_EN_1, 0x04); // select push-pull, active high interrupts
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_INT_MAP_1, 0x80); // select INT3 (intGYRO1) as GYRO data ready interrupt
// writeByte(BMX055_GYRO_ADDRESS, BMX055_GYRO_BGW_SPI3_WDT, 0x06); // Enable watchdog timer for I2C with 50 ms window
// Configure magnetometer
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x82); // Softreset magnetometer, ends up in sleep mode
delay(100);
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL1, 0x01); // Wake up magnetometer
delay(100);
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3); // Normal mode
//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_PWR_CNTL2, MODR << 3 | 0x02); // Forced mode
//writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_INT_EN_2, 0x84); // Enable data ready pin interrupt, active high
// Set up four standard configurations for the magnetometer
switch (Mmode)
{
case lowPower:
// Low-power
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x01); // 3 repetitions (oversampling)
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x02); // 3 repetitions (oversampling)
break;
case Regular:
// Regular
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x04); // 9 repetitions (oversampling)
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x16); // 15 repetitions (oversampling)
break;
case enhancedRegular:
// Enhanced Regular
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x07); // 15 repetitions (oversampling)
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x22); // 27 repetitions (oversampling)
break;
case highAccuracy:
// High Accuracy
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_XY, 0x17); // 47 repetitions (oversampling)
writeByte(BMX055_MAG_ADDRESS, BMX055_MAG_REP_Z, 0x51); // 83 repetitions (oversampling)
break;
}
}
void fastcompaccelBMX055(float * dest1)
{
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x80); // set all accel offset compensation registers to zero
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_SETTING, 0x20); // set offset targets to 0, 0, and +1 g for x, y, z axes
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x20); // calculate x-axis offset
byte c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
while(!(c & 0x10)) { // check if fast calibration complete
c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
delay(10);
}
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x40); // calculate y-axis offset
c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
while(!(c & 0x10)) { // check if fast calibration complete
c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
delay(10);
}
writeByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL, 0x60); // calculate z-axis offset
c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
while(!(c & 0x10)) { // check if fast calibration complete
c = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_CTRL);
delay(10);
}
int8_t compx = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_X);
int8_t compy = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Y);
int8_t compz = readByte(BMX055_ACC_ADDRESS, BMX055_ACC_OFC_OFFSET_Z);
dest1[0] = (float) compx/128.; // accleration bias in g
dest1[1] = (float) compy/128.; // accleration bias in g
dest1[2] = (float) compz/128.; // accleration bias in g
}
/*
// Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
// of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
void accelgyrocalBMX055(float * dest1, float * dest2)
{
uint8_t data[6] = {0, 0, 0, 0, 0, 0};
int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
uint16_t samples, ii;
Serial.println("Calibrating gyro...");
// First get gyro bias
byte c = readByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G);
writeByte(BMX055G_ADDRESS, BMX055G_CTRL_REG5_G, c | 0x40); // Enable gyro FIFO
delay(200); // Wait for change to take effect
writeByte(BMX055G_ADDRESS, BMX055G_FIFO_CTRL_REG_G, 0x20 | 0x1F); // Enable gyro FIFO stream mode and set watermark at 32 samples
delay(1000); // delay 1000 milliseconds to collect FIFO samples
samples = (readByte(BMX055G_ADDRESS, BMX055G_FIFO_SRC_REG_G) & 0x1F); // Read number of stored samples
for(ii = 0; ii < samples ; ii++) { // Read the gyro data stored in the FIFO
int16_t gyro_temp[3] = {0, 0, 0};
readBytes(BMX055G_ADDRESS, BMX055G_OUT_X_L_G, 6, &data[0]);
gyro_temp[0] = (int16_t) (((int16_t)data[1] << 8) | data[0]); // Form signed 16-bit integer for each sample in FIFO
gyro_temp[1] = (int16_t) (((int16_t)data[3] << 8) | data[2]);
gyro_temp[2] = (int16_t) (((int16_t)data[5] << 8) | data[4]);
gyro_bias[0] += (int32_t) gyro_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
gyro_bias[1] += (int32_t) gyro_temp[1];
gyro_bias[2] += (int32_t) gyro_temp[2];
}
gyro_bias[0] /= samples; // average the data