forked from multiwii/multiwii-firmware
-
Notifications
You must be signed in to change notification settings - Fork 12
/
Sensors.cpp
1640 lines (1450 loc) · 63.2 KB
/
Sensors.cpp
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
#include "Arduino.h"
#include "config.h"
#include "def.h"
#include "types.h"
#include "MahoWii.h"
#include "Alarms.h"
#include "EEPROM.h"
#include "IMU.h"
#include "LCD.h"
#include "Sensors.h"
#include "AltHold.h"
static void Device_Mag_getADC();
static void Baro_init();
static void Mag_init();
static void ACC_init();
// ************************************************************************************************************
// board orientation and setup
// ************************************************************************************************************
//default board orientation
#if !defined(ACC_ORIENTATION)
#define ACC_ORIENTATION(X, Y, Z) {imu.accADC[ROLL] = X; imu.accADC[PITCH] = Y; imu.accADC[YAW] = Z;}
#endif
#if !defined(GYRO_ORIENTATION)
#define GYRO_ORIENTATION(X, Y, Z) {imu.gyroADC[ROLL] = X; imu.gyroADC[PITCH] = Y; imu.gyroADC[YAW] = Z;}
#endif
#if !defined(MAG_ORIENTATION)
#define MAG_ORIENTATION(X, Y, Z) {imu.magADC[ROLL] = X; imu.magADC[PITCH] = Y; imu.magADC[YAW] = Z;}
#endif
//ITG3200 / ITG3205 / ITG3050 / MPU6050 / MPU3050 Gyro LPF setting
#if defined(GYRO_LPF_256HZ) || defined(GYRO_LPF_188HZ) || defined(GYRO_LPF_98HZ) || defined(GYRO_LPF_42HZ) || defined(GYRO_LPF_20HZ) || defined(GYRO_LPF_10HZ) || defined(GYRO_LPF_5HZ)
#if defined(GYRO_LPF_256HZ)
#define GYRO_DLPF_CFG 0
#endif
#if defined(GYRO_LPF_188HZ)
#define GYRO_DLPF_CFG 1
#endif
#if defined(GYRO_LPF_98HZ)
#define GYRO_DLPF_CFG 2
#endif
#if defined(GYRO_LPF_42HZ)
#define GYRO_DLPF_CFG 3
#endif
#if defined(GYRO_LPF_20HZ)
#define GYRO_DLPF_CFG 4
#endif
#if defined(GYRO_LPF_10HZ)
#define GYRO_DLPF_CFG 5
#endif
#if defined(GYRO_LPF_5HZ)
#define GYRO_DLPF_CFG 6
#endif
#else
#define GYRO_DLPF_CFG 4 //Default settings LPF 20HZ
#endif
static uint8_t rawADC[6];
#if defined(WMP)
static uint32_t neutralizeTime = 0;
#endif
// ************************************************************************************************************
// I2C general functions
// ************************************************************************************************************
void i2c_init(void) {
#if defined(INTERNAL_I2C_PULLUPS)
I2C_PULLUPS_ENABLE
#else
I2C_PULLUPS_DISABLE
#endif
TWSR = 0; // no prescaler => prescaler = 1
TWBR = ((F_CPU / 400000) - 16) / 2; // set the I2C clock rate to 400kHz
TWCR = 1<<TWEN; // enable twi module, no interrupt
i2c_errors_count = 0;
}
void __attribute__ ((noinline)) waitTransmissionI2C(uint8_t twcr) {
TWCR = twcr;
uint8_t count = 255;
while (!(TWCR & (1<<TWINT))) {
count--;
if (count==0) { //we are in a blocking state => we don't insist
TWCR = 0; //and we force a reset on TWINT register
#if defined(WMP)
neutralizeTime = micros(); //we take a timestamp here to neutralize the value during a short delay
#endif
i2c_errors_count++;
break;
}
}
}
void i2c_rep_start(uint8_t address) {
waitTransmissionI2C((1<<TWINT) | (1<<TWSTA) | (1<<TWEN)); // send REPEAT START condition and wait until transmission completed
TWDR = address; // send device address
waitTransmissionI2C((1<<TWINT) | (1<<TWEN)); // wail until transmission completed
}
void i2c_stop(void) {
TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO);
// while(TWCR & (1<<TWSTO)); // <- can produce a blocking state with some WMP clones
}
void i2c_write(uint8_t data ) {
TWDR = data; // send data to the previously addressed device
waitTransmissionI2C((1<<TWINT) | (1<<TWEN));
}
uint8_t i2c_readAck() {
waitTransmissionI2C((1<<TWINT) | (1<<TWEN) | (1<<TWEA));
return TWDR;
}
uint8_t i2c_readNak() {
waitTransmissionI2C((1<<TWINT) | (1<<TWEN));
uint8_t r = TWDR;
i2c_stop();
return r;
}
void i2c_read_reg_to_buf(uint8_t add, uint8_t reg, uint8_t *buf, uint8_t size) {
i2c_rep_start(add<<1); // I2C write direction
i2c_write(reg); // register selection
i2c_rep_start((add<<1) | 1); // I2C read direction
uint8_t *b = buf;
while (--size) *b++ = i2c_readAck(); // acknowledge all but the final byte
*b = i2c_readNak();
}
void i2c_getSixRawADC(uint8_t add, uint8_t reg) {
i2c_read_reg_to_buf(add, reg, rawADC, 6);
}
void i2c_writeReg(uint8_t add, uint8_t reg, uint8_t val) {
i2c_rep_start(add<<1); // I2C write direction
i2c_write(reg); // register selection
i2c_write(val); // value to write in register
i2c_stop();
}
uint8_t i2c_readReg(uint8_t add, uint8_t reg) {
uint8_t val;
i2c_read_reg_to_buf(add, reg, &val, 1);
return val;
}
// ****************
// GYRO common part
// ****************
void GYRO_Common() {
static int16_t previousGyroADC[3] = {0,0,0};
static int32_t g[3];
uint8_t axis, tilt=0;
#if defined MMGYRO
// Moving Average Gyros by Magnetron1
//---------------------------------------------------
static int16_t mediaMobileGyroADC[3][MMGYROVECTORLENGTH];
static int32_t mediaMobileGyroADCSum[3];
static uint8_t mediaMobileGyroIDX;
//---------------------------------------------------
#endif
if (calibratingG > 0) {
for (axis = 0; axis < 3; axis++) {
if (calibratingG == 512) { // Reset g[axis] at start of calibration
g[axis] = 0;
#if defined(GYROCALIBRATIONFAILSAFE)
previousGyroADC[axis] = imu.gyroADC[axis];
}
if (calibratingG % 10 == 0) {
if (abs(imu.gyroADC[axis] - previousGyroADC[axis]) > 8) {
tilt = 1;
}
previousGyroADC[axis] = imu.gyroADC[axis];
#endif
}
g[axis] += imu.gyroADC[axis]; // Sum up 512 readings
//gyroZero[axis] = g[axis] >> 9;
gyroZero[axis] = g[axis] >> 5; // increase gyro bias precision to 2^(9-5)=16 times
if (calibratingG == 1) {
SET_ALARM_BUZZER(ALRM_FAC_CONFIRM, ALRM_LVL_CONFIRM_ELSE);
}
}
#if defined(GYROCALIBRATIONFAILSAFE)
if (tilt) {
calibratingG = 1000;
LEDPIN_ON;
} else {
calibratingG--;
LEDPIN_OFF;
}
return;
#else
calibratingG--;
#endif
}
#ifdef MMGYRO
mediaMobileGyroIDX = ++mediaMobileGyroIDX % conf.mmgyro;
for (axis = 0; axis < 3; axis++) {
//imu.gyroADC[axis] -= gyroZero[axis];
imu.gyroADC[axis] = ( (((int32_t)imu.gyroADC[axis]) << 4) - gyroZero[axis]) >> 4; // increase gyro bias precision to 2^(9-5)=16 times
mediaMobileGyroADCSum[axis] -= mediaMobileGyroADC[axis][mediaMobileGyroIDX];
//anti gyro glitch, limit the variation between two consecutive readings
mediaMobileGyroADC[axis][mediaMobileGyroIDX] = constrain(imu.gyroADC[axis],previousGyroADC[axis]-800,previousGyroADC[axis]+800);
mediaMobileGyroADCSum[axis] += mediaMobileGyroADC[axis][mediaMobileGyroIDX];
imu.gyroADC[axis] = mediaMobileGyroADCSum[axis] / conf.mmgyro;
#else
for (axis = 0; axis < 3; axis++) {
//imu.gyroADC[axis] -= gyroZero[axis];
imu.gyroADC[axis] = ( (((int32_t)imu.gyroADC[axis]) << 4) - gyroZero[axis]) >> 4; // increase gyro bias precision to 2^(9-5)=16 times
//anti gyro glitch, limit the variation between two consecutive readings
imu.gyroADC[axis] = constrain(imu.gyroADC[axis],previousGyroADC[axis]-800,previousGyroADC[axis]+800);
#endif
previousGyroADC[axis] = imu.gyroADC[axis];
}
#if defined(SENSORS_TILT_45DEG_LEFT)
int16_t temp = ((imu.gyroADC[PITCH] - imu.gyroADC[ROLL] )*7)/10;
imu.gyroADC[ROLL] = ((imu.gyroADC[ROLL] + imu.gyroADC[PITCH])*7)/10;
imu.gyroADC[PITCH]= temp;
#endif
#if defined(SENSORS_TILT_45DEG_RIGHT)
int16_t temp = ((imu.gyroADC[PITCH] + imu.gyroADC[ROLL] )*7)/10;
imu.gyroADC[ROLL] = ((imu.gyroADC[ROLL] - imu.gyroADC[PITCH])*7)/10;
imu.gyroADC[PITCH]= temp;
#endif
}
// ****************
// ACC common part
// ****************
void ACC_Common() {
static int32_t a[3];
static uint8_t curAxis = YAW;
static int16_t limits[3][2] = { {0,0}, {0,0}, {0,0} };
if (calibratingA > 0) {
for (uint8_t axis = 0; axis < 3; axis++) {
// Reset a[axis] at start of calibration
if (calibratingA == 512) {
// Find which axis to calibrate?
int8_t axis2 = (axis + 1) % 3;
int8_t axis3 = (axis + 2) % 3;
if ( abs(imu.accADC[axis] - global_conf.accZero[axis]) > abs(imu.accADC[axis2] - global_conf.accZero[axis2])
&& abs(imu.accADC[axis] - global_conf.accZero[axis]) > abs(imu.accADC[axis3] - global_conf.accZero[axis3])) {
curAxis = axis;
global_conf.accZero[curAxis] = 0;
global_conf.accScale[curAxis] = 0; // re-calibrate scale, too
}
a[axis] = 0;
}
// Sum up 512 readings
a[axis] += imu.accADC[axis];
}
// Clear global variables for next reading and indicate curAxis in GUI by set to zero during calibration
imu.accADC[curAxis] = 0;
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
if (calibratingA == 1) {
int8_t curLimit = a[curAxis] > 0 ? 0 : 1; // positive - 0, negative = 1
limits[curAxis][curLimit] = a[curAxis] >> 9;
// If we get 2 limits for one axis, we can found precise zero and scale
if (limits[curAxis][0] > 0 && limits[curAxis][1] < 0) {
global_conf.accZero[curAxis] = (limits[curAxis][0] + limits[curAxis][1]) / 2;
global_conf.accScale[curAxis] = ((int32_t) ACC_1G) * 2048 / (limits[curAxis][0] - limits[curAxis][1]);
}
// Old (not precise) calibration for Z only
else if (curAxis == YAW && curLimit == 0) {
for (uint8_t axis = 0; axis < 3; axis++) {
global_conf.accZero[axis] = a[axis] >> 9;
if (axis == YAW) {
global_conf.accZero[axis] -= ACC_1G;
}
global_conf.accScale[axis] = 0;
}
}
conf.angleTrim[ROLL] = 0;
conf.angleTrim[PITCH] = 0;
writeGlobalSet(1); // write accZero in EEPROM
}
calibratingA--;
}
/*if (calibratingA>0) {
calibratingA--;
for (uint8_t axis = 0; axis < 3; axis++) {
if (calibratingA == 511) a[axis]=0; // Reset a[axis] at start of calibration
a[axis] +=imu.accADC[axis]; // Sum up 512 readings
global_conf.accZero[axis] = a[axis]>>9; // Calculate average, only the last itteration where (calibratingA == 0) is relevant
}
if (calibratingA == 0) {
global_conf.accZero[YAW] -= ACC_1G; // shift Z down by ACC_1G and store values in EEPROM at end of calibration
conf.angleTrim[ROLL] = 0;
conf.angleTrim[PITCH] = 0;
writeGlobalSet(1); // write accZero in EEPROM
}
}*/
#if defined(INFLIGHT_ACC_CALIBRATION)
static int32_t b[3];
static int16_t accZero_saved[3] = {0,0,0};
static int16_t angleTrim_saved[2] = {0, 0};
//Saving old zeropoints before measurement
if (InflightcalibratingA==50) {
accZero_saved[ROLL] = global_conf.accZero[ROLL] ;
accZero_saved[PITCH] = global_conf.accZero[PITCH];
accZero_saved[YAW] = global_conf.accZero[YAW] ;
angleTrim_saved[ROLL] = conf.angleTrim[ROLL] ;
angleTrim_saved[PITCH] = conf.angleTrim[PITCH] ;
}
if (InflightcalibratingA>0) {
for (uint8_t axis = 0; axis < 3; axis++) {
// Reset a[axis] at start of calibration
if (InflightcalibratingA == 50) b[axis]=0;
// Sum up 50 readings
b[axis] +=imu.accADC[axis];
// Clear global variables for next reading
imu.accADC[axis]=0;
global_conf.accZero[axis]=0;
}
//all values are measured
if (InflightcalibratingA == 1) {
AccInflightCalibrationActive = 0;
AccInflightCalibrationMeasurementDone = 1;
SET_ALARM_BUZZER(ALRM_FAC_CONFIRM, ALRM_LVL_CONFIRM_1); //buzzer for indicatiing the end of calibration
// recover saved values to maintain current flight behavior until new values are transferred
global_conf.accZero[ROLL] = accZero_saved[ROLL] ;
global_conf.accZero[PITCH] = accZero_saved[PITCH];
global_conf.accZero[YAW] = accZero_saved[YAW] ;
conf.angleTrim[ROLL] = angleTrim_saved[ROLL] ;
conf.angleTrim[PITCH] = angleTrim_saved[PITCH] ;
}
InflightcalibratingA--;
}
// Calculate average, shift Z down by ACC_1G and store values in EEPROM at end of calibration
if (AccInflightCalibrationSavetoEEProm == 1){ //the copter is landed, disarmed and the combo has been done again
AccInflightCalibrationSavetoEEProm = 0;
global_conf.accZero[ROLL] = b[ROLL]/50;
global_conf.accZero[PITCH] = b[PITCH]/50;
global_conf.accZero[YAW] = b[YAW]/50-ACC_1G;
conf.angleTrim[ROLL] = 0;
conf.angleTrim[PITCH] = 0;
writeGlobalSet(1); // write accZero in EEPROM
}
#endif
// imu.accADC[ROLL] -= global_conf.accZero[ROLL] ;
// imu.accADC[PITCH] -= global_conf.accZero[PITCH];
// imu.accADC[YAW] -= global_conf.accZero[YAW] ;
// Calibrate
for (uint8_t axis = 0; axis < 3; axis++) {
if (global_conf.accScale[axis]) {
//imu.accADC[axis] = ((int32_t) (imu.accADC[axis] - global_conf.accZero[axis])) * global_conf.accScale[axis] / 1024;
imu.accADC[axis] = (((int32_t) (imu.accADC[axis] - global_conf.accZero[axis])) * global_conf.accScale[axis]) >> 10; // divide by 1024
} else {
imu.accADC[axis] -= global_conf.accZero[axis];
}
}
#if defined(SENSORS_TILT_45DEG_LEFT)
int16_t temp = ((imu.accADC[PITCH] - imu.accADC[ROLL] )*7)/10;
imu.accADC[ROLL] = ((imu.accADC[ROLL] + imu.accADC[PITCH])*7)/10;
imu.accADC[PITCH] = temp;
#endif
#if defined(SENSORS_TILT_45DEG_RIGHT)
int16_t temp = ((imu.accADC[PITCH] + imu.accADC[ROLL] )*7)/10;
imu.accADC[ROLL] = ((imu.accADC[ROLL] - imu.accADC[PITCH])*7)/10;
imu.accADC[PITCH] = temp;
#endif
}
// ************************************************************************************************************
// BARO section
// ************************************************************************************************************
#if BARO
#define BARO_TAB_SIZE 21
static void Baro_Common() {
static int32_t baroHistTab[BARO_TAB_SIZE];
static uint8_t baroHistIdx;
uint8_t indexplus1 = (baroHistIdx + 1);
if (indexplus1 == BARO_TAB_SIZE) indexplus1 = 0;
baroHistTab[baroHistIdx] = baroPressure;
baroPressureSum += baroHistTab[baroHistIdx];
baroPressureSum -= baroHistTab[indexplus1];
baroHistIdx = indexplus1;
}
#endif
// ************************************************************************************************************
// I2C Barometer BOSCH BMP085
// ************************************************************************************************************
// I2C adress: 0x77 (7bit)
// principle:
// 1) read the calibration register (only once at the initialization)
// 2) read uncompensated temperature (not mandatory at every cycle)
// 3) read uncompensated pressure
// 4) raw temp + raw pressure => calculation of the adjusted pressure
// the following code uses the maximum precision setting (oversampling setting 3)
// ************************************************************************************************************
#if defined(BMP085)
#define BMP085_ADDRESS 0x77
static struct {
// sensor registers from the BOSCH BMP085 datasheet
int16_t ac1, ac2, ac3;
uint16_t ac4, ac5, ac6;
int16_t b1, b2, mb, mc, md;
union {uint16_t val; uint8_t raw[2]; } ut; //uncompensated T
union {uint32_t val; uint8_t raw[4]; } up; //uncompensated P
uint8_t state;
uint32_t deadline;
} bmp085_ctx;
#define OSS 3
/* transform a series of bytes from big endian to little
endian and vice versa. */
void swap_endianness(void *buf, size_t size) {
/* we swap in-place, so we only have to
* place _one_ element on a temporary tray
*/
uint8_t tray;
uint8_t *from;
uint8_t *to;
/* keep swapping until the pointers have assed each other */
for (from = (uint8_t*)buf, to = &from[size-1]; from < to; from++, to--) {
tray = *from;
*from = *to;
*to = tray;
}
}
void i2c_BMP085_readCalibration(){
delay(10);
//read calibration data in one go
size_t s_bytes = (uint8_t*)&bmp085_ctx.md - (uint8_t*)&bmp085_ctx.ac1 + sizeof(bmp085_ctx.ac1);
i2c_read_reg_to_buf(BMP085_ADDRESS, 0xAA, (uint8_t*)&bmp085_ctx.ac1, s_bytes);
// now fix endianness
int16_t *p;
for (p = &bmp085_ctx.ac1; p <= &bmp085_ctx.md; p++) {
swap_endianness(p, sizeof(*p));
}
}
// read uncompensated temperature value: send command first
void i2c_BMP085_UT_Start(void) {
i2c_writeReg(BMP085_ADDRESS,0xf4,0x2e);
i2c_rep_start(BMP085_ADDRESS<<1);
i2c_write(0xF6);
i2c_stop();
}
// read uncompensated pressure value: send command first
void i2c_BMP085_UP_Start () {
i2c_writeReg(BMP085_ADDRESS,0xf4,0x34+(OSS<<6)); // control register value for oversampling setting 3
i2c_rep_start(BMP085_ADDRESS<<1); //I2C write direction => 0
i2c_write(0xF6);
i2c_stop();
}
// read uncompensated pressure value: read result bytes
// the datasheet suggests a delay of 25.5 ms (oversampling settings 3) after the send command
void i2c_BMP085_UP_Read () {
i2c_rep_start((BMP085_ADDRESS<<1) | 1);//I2C read direction => 1
bmp085_ctx.up.raw[2] = i2c_readAck();
bmp085_ctx.up.raw[1] = i2c_readAck();
bmp085_ctx.up.raw[0] = i2c_readNak();
}
// read uncompensated temperature value: read result bytes
// the datasheet suggests a delay of 4.5 ms after the send command
void i2c_BMP085_UT_Read() {
i2c_rep_start((BMP085_ADDRESS<<1) | 1);//I2C read direction => 1
bmp085_ctx.ut.raw[1] = i2c_readAck();
bmp085_ctx.ut.raw[0] = i2c_readNak();
}
void i2c_BMP085_Calculate() {
int32_t x1, x2, x3, b3, b5, b6, p, tmp;
uint32_t b4, b7;
// Temperature calculations
x1 = ((int32_t)bmp085_ctx.ut.val - bmp085_ctx.ac6) * bmp085_ctx.ac5 >> 15;
x2 = ((int32_t)bmp085_ctx.mc << 11) / (x1 + bmp085_ctx.md);
b5 = x1 + x2;
baroTemperature = (b5 * 10 + 8) >> 4; // in 0.01 degC (same as MS561101BA temperature)
// Pressure calculations
b6 = b5 - 4000;
x1 = (bmp085_ctx.b2 * (b6 * b6 >> 12)) >> 11;
x2 = bmp085_ctx.ac2 * b6 >> 11;
x3 = x1 + x2;
tmp = bmp085_ctx.ac1;
tmp = (tmp*4 + x3) << OSS;
b3 = (tmp+2)/4;
x1 = bmp085_ctx.ac3 * b6 >> 13;
x2 = (bmp085_ctx.b1 * (b6 * b6 >> 12)) >> 16;
x3 = ((x1 + x2) + 2) >> 2;
b4 = (bmp085_ctx.ac4 * (uint32_t)(x3 + 32768)) >> 15;
b7 = ((uint32_t) (bmp085_ctx.up.val >> (8-OSS)) - b3) * (50000 >> OSS);
p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;
x1 = (p >> 8) * (p >> 8);
x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16;
baroPressure = p + ((x1 + x2 + 3791) >> 4);
}
void Baro_init() {
delay(10);
i2c_BMP085_readCalibration();
delay(5);
i2c_BMP085_UT_Start();
bmp085_ctx.deadline = currentTime+5000;
}
//return 0: no data available, no computation ; 1: new value available ; 2: no new value, but computation time
uint8_t Baro_update() { // first UT conversion is started in init procedure
if (currentTime < bmp085_ctx.deadline) return 0;
bmp085_ctx.deadline = currentTime+6000; // 1.5ms margin according to the spec (4.5ms T convetion time)
if (bmp085_ctx.state == 0) {
i2c_BMP085_UT_Read();
i2c_BMP085_UP_Start();
bmp085_ctx.state = 1;
Baro_Common();
bmp085_ctx.deadline += 21000; // 6000+21000=27000 1.5ms margin according to the spec (25.5ms P convetion time with OSS=3)
return 1;
} else {
i2c_BMP085_UP_Read();
i2c_BMP085_UT_Start();
i2c_BMP085_Calculate();
bmp085_ctx.state = 0;
return 2;
}
}
#endif
// ************************************************************************************************************
// I2C Barometer MS561101BA
// ************************************************************************************************************
//
// specs are here: http://www.meas-spec.com/downloads/MS5611-01BA03.pdf
// useful info on pages 7 -> 12
#if defined(MS561101BA)
#if !defined(MS561101BA_ADDRESS)
#define MS561101BA_ADDRESS 0x77 //CBR=0 0xEE I2C address when pin CSB is connected to LOW (GND)
//#define MS561101BA_ADDRESS 0x76 //CBR=1 0xEC I2C address when pin CSB is connected to HIGH (VCC)
#endif
// registers of the device
#define MS561101BA_PRESSURE 0x40
#define MS561101BA_TEMPERATURE 0x50
#define MS561101BA_RESET 0x1E
// OSR (Over Sampling Ratio) constants
#define MS561101BA_OSR_256 0x00
#define MS561101BA_OSR_512 0x02
#define MS561101BA_OSR_1024 0x04
#define MS561101BA_OSR_2048 0x06
#define MS561101BA_OSR_4096 0x08
#define OSR MS561101BA_OSR_4096
static struct {
// sensor registers from the MS561101BA datasheet
uint16_t c[7];
uint32_t ut; //uncompensated T
uint32_t up; //uncompensated P
uint8_t state;
uint16_t deadline;
} ms561101ba_ctx;
static void Baro_init() {
//reset
i2c_writeReg(MS561101BA_ADDRESS, MS561101BA_RESET, 0);
delay(100);
//read calibration data
union {uint16_t val; uint8_t raw[2]; } data;
for(uint8_t i=0;i<6;i++) {
i2c_rep_start(MS561101BA_ADDRESS<<1);
i2c_write(0xA2+2*i);
i2c_rep_start((MS561101BA_ADDRESS<<1) | 1);//I2C read direction => 1
data.raw[1] = i2c_readAck(); // read a 16 bit register
data.raw[0] = i2c_readNak();
ms561101ba_ctx.c[i+1] = data.val;
}
}
// read uncompensated temperature or pressure value: send command first
static void i2c_MS561101BA_UT_or_UP_Start(uint8_t reg) {
i2c_rep_start(MS561101BA_ADDRESS<<1); // I2C write direction
i2c_write(reg); // register selection
i2c_stop();
}
static void i2c_MS561101BA_UT_or_UP_Read(uint32_t* val) {
union {uint32_t val; uint8_t raw[4]; } data;
i2c_rep_start(MS561101BA_ADDRESS<<1);
i2c_write(0);
i2c_rep_start((MS561101BA_ADDRESS<<1) | 1);
data.raw[2] = i2c_readAck();
data.raw[1] = i2c_readAck();
data.raw[0] = i2c_readNak();
*val = data.val;
}
// use float approximation instead of int64_t intermediate values
// does not use 2nd order compensation under -15 deg
static void i2c_MS561101BA_Calculate() {
int32_t delt;
float dT = (int32_t)ms561101ba_ctx.ut - (int32_t)((uint32_t)ms561101ba_ctx.c[5] << 8);
float off = ((uint32_t)ms561101ba_ctx.c[2] <<16) + ((dT * ms561101ba_ctx.c[4]) /((uint32_t)1<<7));
float sens = ((uint32_t)ms561101ba_ctx.c[1] <<15) + ((dT * ms561101ba_ctx.c[3]) /((uint32_t)1<<8));
delt = (dT * ms561101ba_ctx.c[6])/((uint32_t)1<<23);
baroTemperature = delt + 2000;
if (delt < 0) { // temperature lower than 20st.C
delt *= 5 * delt;
off -= delt>>1;
sens -= delt>>2;
}
baroPressure = (( (ms561101ba_ctx.up * sens ) /((uint32_t)1<<21)) - off)/((uint32_t)1<<15);
}
//return 0: no data available, no computation ; 1: new value available or no new value but computation time
uint8_t Baro_update() { // first UT conversion is started in init procedure
uint32_t* rawValPointer;
uint8_t commandRegister;
if (ms561101ba_ctx.state == 2) { // a third state is introduced here to isolate calculate() and smooth timecycle spike
ms561101ba_ctx.state = 0;
i2c_MS561101BA_Calculate();
return 1;
}
if ((int16_t)(currentTime - ms561101ba_ctx.deadline)<0) return 0; // the initial timer is not initialized, but in any case, no more than 65ms to wait.
ms561101ba_ctx.deadline = currentTime+10000; // UT and UP conversion take 8.5ms so we do next reading after 10ms
if (ms561101ba_ctx.state == 0) {
Baro_Common(); // moved here for less timecycle spike, goes after i2c_MS561101BA_Calculate
rawValPointer = &ms561101ba_ctx.ut;
commandRegister = MS561101BA_PRESSURE + OSR;
} else {
rawValPointer = &ms561101ba_ctx.up;
commandRegister = MS561101BA_TEMPERATURE + OSR;
}
ms561101ba_ctx.state++;
i2c_MS561101BA_UT_or_UP_Read(rawValPointer); // get the 24bit resulting from a UP of UT command request. Nothing interresting for the first cycle because we don't initiate a command in Baro_init()
i2c_MS561101BA_UT_or_UP_Start(commandRegister); // send the next command to get UP or UT value after at least 8.5ms
return 1;
}
#endif
// ************************************************************************************************************
// I2C Accelerometer MMA7455
// ************************************************************************************************************
#if defined(MMA7455)
#if !defined(MMA7455_ADDRESS)
#define MMA7455_ADDRESS 0x1D
#endif
void ACC_init () {
delay(10);
i2c_writeReg(MMA7455_ADDRESS,0x16,0x21);
}
void ACC_getADC () {
i2c_getSixRawADC(MMA7455_ADDRESS,0x00);
ACC_ORIENTATION( ((int8_t(rawADC[1])<<8) | int8_t(rawADC[0])) ,
((int8_t(rawADC[3])<<8) | int8_t(rawADC[2])) ,
((int8_t(rawADC[5])<<8) | int8_t(rawADC[4])) );
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer MMA8451Q
// ************************************************************************************************************
#if defined(MMA8451Q)
#if !defined(MMA8451Q_ADDRESS)
#define MMA8451Q_ADDRESS 0x1C
//#define MMA8451Q_ADDRESS 0x1D
#endif
void ACC_init () {
delay(10);
i2c_writeReg(MMA8451Q_ADDRESS,0x2A,0x05); // wake up & low noise
delay(10);
i2c_writeReg(MMA8451Q_ADDRESS,0x0E,0x02); // full scale range
}
void ACC_getADC () {
i2c_getSixRawADC(MMA8451Q_ADDRESS,0x00);
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])/32 ,
((rawADC[3]<<8) | rawADC[2])/32 ,
((rawADC[5]<<8) | rawADC[4])/32);
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer ADXL345
// ************************************************************************************************************
// I2C adress: 0x3A (8bit) 0x1D (7bit)
// Resolution: 10bit (Full range - 14bit, but this is autoscaling 10bit ADC to the range +- 16g)
// principle:
// 1) CS PIN must be linked to VCC to select the I2C mode
// 2) SD0 PIN must be linked to VCC to select the right I2C adress
// 3) bit b00000100 must be set on register 0x2D to read data (only once at the initialization)
// 4) bits b00001011 must be set on register 0x31 to select the data format (only once at the initialization)
// ************************************************************************************************************
#if defined(ADXL345)
#if !defined(ADXL345_ADDRESS)
#define ADXL345_ADDRESS 0x1D
//#define ADXL345_ADDRESS 0x53 //WARNING: Conflicts with a Wii Motion plus!
#endif
void ACC_init () {
delay(10);
i2c_writeReg(ADXL345_ADDRESS,0x2D,1<<3); // register: Power CTRL -- value: Set measure bit 3 on
i2c_writeReg(ADXL345_ADDRESS,0x31,0x0B); // register: DATA_FORMAT -- value: Set bits 3(full range) and 1 0 on (+/- 16g-range)
i2c_writeReg(ADXL345_ADDRESS,0x2C,0x09); // register: BW_RATE -- value: rate=50hz, bw=20hz
}
void ACC_getADC () {
i2c_getSixRawADC(ADXL345_ADDRESS,0x32);
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0]) ,
((rawADC[3]<<8) | rawADC[2]) ,
((rawADC[5]<<8) | rawADC[4]) );
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer BMA180
// ************************************************************************************************************
// I2C adress: 0x80 (8bit) 0x40 (7bit) (SDO connection to VCC)
// I2C adress: 0x82 (8bit) 0x41 (7bit) (SDO connection to VDDIO)
// Resolution: 14bit
//
// Control registers:
//
// 0x20 bw_tcs: | bw<3:0> | tcs<3:0> |
// | 150Hz | xxxxxxxx |
// 0x30 tco_z: | tco_z<5:0> | mode_config<1:0> |
// | xxxxxxxxxx | 00 |
// 0x35 offset_lsb1: | offset_x<3:0> | range<2:0> | smp_skip |
// | xxxxxxxxxxxxx | 8G: 101 | xxxxxxxx |
// ************************************************************************************************************
#if defined(BMA180)
#if !defined(BMA180_ADDRESS)
#define BMA180_ADDRESS 0x40
//#define BMA180_ADDRESS 0x41
#endif
void ACC_init () {
delay(10);
//default range 2G: 1G = 4096 unit.
i2c_writeReg(BMA180_ADDRESS,0x0D,1<<4); // register: ctrl_reg0 -- value: set bit ee_w to 1 to enable writing
delay(5);
uint8_t control = i2c_readReg(BMA180_ADDRESS, 0x20);
control = control & 0x0F; // save tcs register
//control = control | (0x01 << 4); // register: bw_tcs reg: bits 4-7 to set bw -- value: set low pass filter to 20Hz
control = control | (0x00 << 4); // set low pass filter to 10Hz (bits value = 0000xxxx)
i2c_writeReg(BMA180_ADDRESS, 0x20, control);
delay(5);
control = i2c_readReg(BMA180_ADDRESS, 0x30);
control = control & 0xFC; // save tco_z register
control = control | 0x00; // set mode_config to 0
i2c_writeReg(BMA180_ADDRESS, 0x30, control);
delay(5);
control = i2c_readReg(BMA180_ADDRESS, 0x35);
control = control & 0xF1; // save offset_x and smp_skip register
control = control | (0x05 << 1); // set range to 8G
i2c_writeReg(BMA180_ADDRESS, 0x35, control);
delay(5);
}
void ACC_getADC () {
i2c_getSixRawADC(BMA180_ADDRESS,0x02);
//usefull info is on the 14 bits [2-15] bits /4 => [0-13] bits /4 => 12 bit resolution
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>4 ,
((rawADC[3]<<8) | rawADC[2])>>4 ,
((rawADC[5]<<8) | rawADC[4])>>4 );
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer BMA280
// ************************************************************************************************************
#if defined(BMA280)
#if !defined(BMA280_ADDRESS)
#define BMA280_ADDRESS 0x18 // SDO PIN on GND
//#define BMA280_ADDRESS 0x19 // SDO PIN on Vddio
#endif
void ACC_init () {
delay(10);
i2c_writeReg(BMA280_ADDRESS, 0x10, 0x09); //set BW to 15,63Hz
delay(5);
i2c_writeReg(BMA280_ADDRESS, 0x0F, 0x08); //set range to 8G
}
void ACC_getADC () {
i2c_getSixRawADC(BMA280_ADDRESS,0x02);
//usefull info is on the 14 bits [2-15] bits /4 => [0-13] bits /4 => 12 bit resolution
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>4 ,
((rawADC[3]<<8) | rawADC[2])>>4 ,
((rawADC[5]<<8) | rawADC[4])>>4 );
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer BMA020
// ************************************************************************************************************
// I2C adress: 0x70 (8bit)
// Resolution: 10bit
// Control registers:
//
// Datasheet: After power on reset or soft reset it is recommended to set the SPI4-bit to the correct value.
// 0x80 = SPI four-wire = Default setting
// | 0x15: | SPI4 | enable_adv_INT | new_data_INT | latch_INT | shadow_dis | wake_up_pause<1:0> | wake_up |
// | | 1 | 0 | 0 | 0 | 0 | 00 | 0 |
//
// | 0x14: | reserved <2:0> | range <1:0> | bandwith <2:0> |
// | | !!Calibration!! | 2g | 25Hz |
//
// ************************************************************************************************************
#if defined(BMA020)
void ACC_init(){
i2c_writeReg(0x38,0x15,0x80); // set SPI4 bit
uint8_t control = i2c_readReg(0x70, 0x14);
control = control & 0xE0; // save bits 7,6,5
control = control | (0x02 << 3); // Range 8G (10)
control = control | 0x00; // Bandwidth 25 Hz 000
i2c_writeReg(0x38,0x14,control);
}
void ACC_getADC(){
i2c_getSixRawADC(0x38,0x02);
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>6 ,
((rawADC[3]<<8) | rawADC[2])>>6 ,
((rawADC[5]<<8) | rawADC[4])>>6 );
ACC_Common();
}
#endif
// ************************************************************************
// LIS3LV02 I2C Accelerometer
// ************************************************************************
#if defined(LIS3LV02)
#define LIS3A 0x1D
void ACC_init(){
i2c_writeReg(LIS3A ,0x20 ,0xD7 ); // CTRL_REG1 1101 0111 Pwr on, 160Hz
i2c_writeReg(LIS3A ,0x21 ,0x50 ); // CTRL_REG2 0100 0000 Littl endian, 12 Bit, Boot
}
void ACC_getADC(){
i2c_getSixRawADC(LIS3A,0x28+0x80);
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>2 ,
((rawADC[3]<<8) | rawADC[2])>>2 ,
((rawADC[5]<<8) | rawADC[4])>>2);
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Accelerometer LSM303DLx
// ************************************************************************************************************
#if defined(LSM303DLx_ACC)
void ACC_init () {
delay(10);
i2c_writeReg(0x18,0x20,0x27);
i2c_writeReg(0x18,0x23,0x30);
i2c_writeReg(0x18,0x21,0x00);
}
void ACC_getADC () {
i2c_getSixRawADC(0x18,0xA8);
ACC_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>4 ,
((rawADC[3]<<8) | rawADC[2])>>4 ,
((rawADC[5]<<8) | rawADC[4])>>4 );
ACC_Common();
}
#endif
// ************************************************************************************************************
// ADC ACC
// ************************************************************************************************************
#if defined(ADCACC)
void ACC_init(){
pinMode(A1,INPUT);
pinMode(A2,INPUT);
pinMode(A3,INPUT);
}
void ACC_getADC() {
ACC_ORIENTATION( analogRead(A1) ,
analogRead(A2) ,
analogRead(A3) );
ACC_Common();
}
#endif
// ************************************************************************************************************
// I2C Gyroscope L3G4200D
// ************************************************************************************************************
#if defined(L3G4200D)
#define L3G4200D_ADDRESS 0x69
void Gyro_init() {
delay(100);
i2c_writeReg(L3G4200D_ADDRESS ,0x20 ,0x8F ); // CTRL_REG1 400Hz ODR, 20hz filter, run!
delay(5);
i2c_writeReg(L3G4200D_ADDRESS ,0x24 ,0x02 ); // CTRL_REG5 low pass filter enable
delay(5);
i2c_writeReg(L3G4200D_ADDRESS ,0x23 ,0x30); // CTRL_REG4 Select 2000dps
}
void Gyro_getADC () {
i2c_getSixRawADC(L3G4200D_ADDRESS,0x80|0x28);
GYRO_ORIENTATION( ((rawADC[1]<<8) | rawADC[0])>>2 ,
((rawADC[3]<<8) | rawADC[2])>>2 ,
((rawADC[5]<<8) | rawADC[4])>>2 );
GYRO_Common();
}
#endif
// ************************************************************************************************************
// I2C Gyroscope ITG3200 / ITG3205 / ITG3050 / MPU3050
// ************************************************************************************************************
// I2C adress: 0xD2 (8bit) 0x69 (7bit)
// I2C adress: 0xD0 (8bit) 0x68 (7bit)
// principle:
// 1) VIO is connected to VDD
// 2) I2C adress is set to 0x69 (AD0 PIN connected to VDD)
// or 2) I2C adress is set to 0x68 (AD0 PIN connected to GND)
// 3) sample rate = 1000Hz ( 1kHz/(div+1) )
// ************************************************************************************************************
#if defined(ITG3200) || defined(ITG3050) || defined(MPU3050)
#if !defined(GYRO_ADDRESS)
#define GYRO_ADDRESS 0X68
//#define GYRO_ADDRESS 0X69
#endif
void Gyro_init() {
i2c_writeReg(GYRO_ADDRESS, 0x3E, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
delay(5);
i2c_writeReg(GYRO_ADDRESS, 0x16, 0x18 + GYRO_DLPF_CFG); //Gyro CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; DLPF_CFG = GYRO_DLPF_CFG ; -- FS_SEL = 3: Full scale set to 2000 deg/sec
delay(5);
i2c_writeReg(GYRO_ADDRESS, 0x3E, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference)
delay(100);
}
void Gyro_getADC () {
i2c_getSixRawADC(GYRO_ADDRESS,0X1D);
GYRO_ORIENTATION( ((rawADC[0]<<8) | rawADC[1])>>2 , // range: +/- 8192; +/- 2000 deg/sec
((rawADC[2]<<8) | rawADC[3])>>2 ,
((rawADC[4]<<8) | rawADC[5])>>2 );
GYRO_Common();
}
#endif
// ************************************************************************************************************
// I2C Compass common function
// ************************************************************************************************************
#if MAG
static float magGain[3] = {1.0,1.0,1.0}; // gain for each axis, populated at sensor init
uint8_t Mag_getADC() { // return 1 when news values are available, 0 otherwise
static uint32_t t, tCal = 0;
static int16_t magZeroTempMin[3], magZeroTempMax[3];
uint8_t axis;
if (!f.CALIBRATE_MAG && currentTime < t) {
return 0; // each read is spaced by 50ms/20hz BUT not during calibration
}
t = currentTime + 50000;