/
LSM9DS1_Driver.c
1978 lines (1604 loc) · 44.8 KB
/
LSM9DS1_Driver.c
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
/*
* LSM9DS1_Driver.c
*
* Created on: 12-02-2016
* Author: Mateusz
*/
#include "LSM9DS1_Driver.h"
#include "LSM9DS1_Registers.h"
#include "LSM9DS1_Types.h"
#include "FIFO_functions.h"
#include "TSL2561.h"
#include <stdint.h>
#include <inttypes.h>
#include <math.h>
#include <stdlib.h>
#include <string.h>
//#define DELAY 10000
#define DELAY 1200
#define READING_DELAY 60
#define LSM9DS1_M 0x1E // Would be 0x1C if SDO_M is LOW
#define LSM9DS1_AG 0x6B // Would be 0x6A if SDO_AG is LOW
char accelOsX[100];
char accelOsY[100];
char accelOsZ[100];
#define TRUE 1
#define FALSE 0
handle_t TimerIdReadMeasurements = 0;
uint32_t StatusTimerReadMeasurements = SYSTM001_ERROR;
volatile bool readingAllowed = TRUE;
accel pomiaryAccel[100];
extern accel copiedData[100];
//accel pomiaryAccel1[100];
addressAndData adrAndData;
//tools for sending MSG
static bool sendMsgTimerExpired = FALSE;
handle_t TimerIDSendMsg = 0;
uint32_t statusTimerSendMsg = SYSTM001_ERROR;
bool sendingInProgress = FALSE;
//tools for sending MSG
int counter = 0;
float magSensitivity[4] = {0.00014, 0.00029, 0.00043, 0.00058};
//linear acceleration all axes
int16_t accelX = 0;
int16_t accelY = 0;
int16_t accelZ = 0;
float accelXf = 0;
float accelYf = 0;
float accelZf = 0;
//linear acceleration all axes
//gyroscope all axes
int16_t gyroX = 0;
int16_t gyroY = 0;
int16_t gyroZ = 0;
float gyroXf = 0;
float gyroYf = 0;
float gyroZf = 0;
//gyroscope all axes
//magnetometer all axes
int16_t magnetX = 0;
int16_t magnetY = 0;
int16_t magnetZ = 0;
float magnetXf = 0;
float magnetYf = 0;
float magnetZf = 0;
//magnetometer all axes
extern char copied = 0;
uint16_t DataReceive1 = 0;
uint8_t received = 0;
float getAccelXf(void)
{
return accelXf;
}
int16_t getAccelX(void)
{
return accelX;
}
float getAccelYf(void)
{
return accelYf;
}
int16_t getAccelY(void)
{
return accelY;
}
float getAccelZf(void)
{
return accelZf;
}
int16_t getAccelZ(void)
{
return accelZ;
}
float getGyroXf(void)
{
return gyroXf;
}
int16_t getGyroX(void)
{
return gyroX;
}
float getGyroYf(void)
{
return gyroYf;
}
int16_t getGyroY(void)
{
return gyroY;
}
float getGyroZf(void)
{
return gyroZf;
}
int16_t getGyroZ(void)
{
return gyroZ;
}
float getMagnetXf(void)
{
return magnetXf;
}
int16_t getMagnetX(void)
{
return magnetX;
}
float getMagnetYf(void)
{
return magnetYf;
}
int16_t getMagnetY(void)
{
return magnetY;
}
float getMagnetZf(void)
{
return magnetZf;
}
int16_t getMagnetZ(void)
{
return magnetZ;
}
void startMeasurements(void)
{
TimerIdReadMeasurements=SYSTM001_CreateTimer(READING_DELAY,SYSTM001_PERIODIC,timerHandlerReceiveOneMeasurementEachSensor,&adrAndData);
SYSTM001_StartTimer(TimerIdReadMeasurements);
}
void startMeasurements1(void)
{
TimerIdReadMeasurements=SYSTM001_CreateTimer(READING_DELAY,SYSTM001_PERIODIC,timerHandlerReceiveOneMeasurementEachSensor1,&adrAndData);
SYSTM001_StartTimer(TimerIdReadMeasurements);
}
void resetMeasurements(void)
{
SYSTM001_StopTimer(TimerIdReadMeasurements);
SYSTM001_DeleteTimer(TimerIdReadMeasurements);
}
void readAndSendMeasurements(void (*sendFunction)(char *str, int len))
{
if(!readingAllowed && (counter < 1))
{
accelX = (adrAndData.dane[1] << 8) | adrAndData.dane[0]; // Store x-axis values into gx
accelY = (adrAndData.dane[3] << 8) | adrAndData.dane[2]; // Store y-axis values into gy
accelZ = (adrAndData.dane[5] << 8) | adrAndData.dane[4]; // Store z-axis values into gz
if (_autoCalc) //kalibracja
{
accelX -= aBiasRaw[X_AXIS];
accelY -= aBiasRaw[Y_AXIS];
accelZ -= aBiasRaw[Z_AXIS];
}
accelXf = calcAccel(accelX);
accelYf = calcAccel(accelY);
accelZf = calcAccel(accelZ);
accelX = calcAccel(accelX);
accelY = calcAccel(accelY);
accelZ = calcAccel(accelZ);
pomiaryAccel[counter].ax = accelX;
pomiaryAccel[counter].ay = accelY;
pomiaryAccel[counter].az = accelZ;
gyroX = (adrAndData.dane[7] << 8) | adrAndData.dane[6];
gyroY = (adrAndData.dane[9] << 8) | adrAndData.dane[8];
gyroZ = (adrAndData.dane[11] << 8) | adrAndData.dane[10];
if (_autoCalc) //kalibracja
{
gyroX -= gBiasRaw[X_AXIS];
gyroY -= gBiasRaw[Y_AXIS];
gyroZ -= gBiasRaw[Z_AXIS];
}
gyroXf = calcGyro(gyroX);
gyroYf = calcGyro(gyroY);
gyroZf = calcGyro(gyroZ);
gyroX = calcGyro(gyroX);
gyroY = calcGyro(gyroY);
gyroZ = calcGyro(gyroZ);
pomiaryAccel[counter].gx = gyroX;
pomiaryAccel[counter].gy = gyroY;
pomiaryAccel[counter].gz = gyroZ;
magnetX = (adrAndData.dane[13] << 8) | adrAndData.dane[12];
magnetY = (adrAndData.dane[15] << 8) | adrAndData.dane[14];
magnetZ = (adrAndData.dane[17] << 8) | adrAndData.dane[16];
magnetXf = calcMag(magnetX);
magnetYf = calcMag(magnetY);
magnetZf = calcMag(magnetZ);
magnetX = calcMag(magnetX);
magnetY = calcMag(magnetY);
magnetZ = calcMag(magnetZ);
counter++;
/*if(counter < 50)
{
readingAllowed = TRUE;
}*/
}
if(counter >= 1/* && copied == 0*/)
{
int i = 0;
/*for(i = 0; i < 50; i++)
{
copiedData[i].ax = pomiaryAccel[i].ax;
copiedData[i].ay = pomiaryAccel[i].ay;
copiedData[i].az = pomiaryAccel[i].az;
copiedData[i].gx = pomiaryAccel[i].gx;
copiedData[i].gy = pomiaryAccel[i].gy;
copiedData[i].gz = pomiaryAccel[i].gz;
}*/
counter = 0;
copied = 1;
readingAllowed = TRUE;
}
}
void initAdrAndSubAdr(void)
{
adrAndData.adr.addressDevice[0] = 0x6B;
adrAndData.adr.addressDevice[1] = 0x1E;
adrAndData.adr.subAddress[0] = OUT_X_L_XL; //subaddres for accel
adrAndData.adr.subAddress[1] = OUT_X_L_G; //sub address for gyroscope
adrAndData.adr.subAddress[2] = OUT_X_L_M;
}
void initLSM9DS1(void)
{
init(IMU_MODE_I2C, LSM9DS1_AG_ADDR(1), LSM9DS1_M_ADDR(1));
settings.device.commInterface = IMU_MODE_I2C;
settings.device.mAddress = LSM9DS1_M;
settings.device.agAddress = LSM9DS1_AG;
initAdrAndSubAdr();
if(!begin())
{
int k = 0;
}
}
void init(interface_mode interface, uint8_t xgAddr, uint8_t mAddr)
{
//measurementsLSMRead = 0;
settings.device.commInterface = interface;
settings.device.agAddress = xgAddr;
settings.device.mAddress = mAddr;
settings.gyro.enabled = TRUE;
settings.gyro.enableX = TRUE;
settings.gyro.enableY = TRUE;
settings.gyro.enableZ = TRUE;
// gyro scale can be 245, 500, or 2000
settings.gyro.scale = 245;
// gyro sample rate: value between 1-6
// 1 = 14.9 4 = 238
// 2 = 59.5 5 = 476
// 3 = 119 6 = 952
settings.gyro.sampleRate = 3;//by³o 3
// gyro cutoff frequency: value between 0-3
// Actual value of cutoff frequency depends
// on sample rate.
settings.gyro.bandwidth = 0;
settings.gyro.lowPowerEnable = FALSE;
settings.gyro.HPFEnable = FALSE;
// Gyro HPF cutoff frequency: value between 0-9
// Actual value depends on sample rate. Only applies
// if gyroHPFEnable is TRUE.
settings.gyro.HPFCutoff = 0;
settings.gyro.flipX = FALSE;
settings.gyro.flipY = FALSE;
settings.gyro.flipZ = FALSE;
settings.gyro.orientation = 0;
settings.gyro.latchInterrupt = TRUE;
settings.accel.enabled = TRUE;
settings.accel.enableX = TRUE;
settings.accel.enableY = TRUE;
settings.accel.enableZ = TRUE;
// accel scale can be 2, 4, 8, or 16
settings.accel.scale = 2;
// accel sample rate can be 1-6
// 1 = 10 Hz 4 = 238 Hz
// 2 = 50 Hz 5 = 476 Hz
// 3 = 119 Hz 6 = 952 Hz
settings.accel.sampleRate = 6;
// Accel cutoff freqeuncy can be any value between -1 - 3.
// -1 = bandwidth determined by sample rate
// 0 = 408 Hz 2 = 105 Hz
// 1 = 211 Hz 3 = 50 Hz
settings.accel.bandwidth = -1;
settings.accel.highResEnable = FALSE;
// accelHighResBandwidth can be any value between 0-3
// LP cutoff is set to a factor of sample rate
// 0 = ODR/50 2 = ODR/9
// 1 = ODR/100 3 = ODR/400
settings.accel.highResBandwidth = 0;
settings.mag.enabled = TRUE;
// mag scale can be 4, 8, 12, or 16
settings.mag.scale = 4;
// mag data rate can be 0-7
// 0 = 0.625 Hz 4 = 10 Hz
// 1 = 1.25 Hz 5 = 20 Hz
// 2 = 2.5 Hz 6 = 40 Hz
// 3 = 5 Hz 7 = 80 Hz
settings.mag.sampleRate = 7;
settings.mag.tempCompensationEnable = FALSE;
// magPerformance can be any value between 0-3
// 0 = Low power mode 2 = high performance
// 1 = medium performance 3 = ultra-high performance
settings.mag.XYPerformance = 3;
settings.mag.ZPerformance = 3;
settings.mag.lowPowerEnable = FALSE;
// magOperatingMode can be 0-2
// 0 = continuous conversion
// 1 = single-conversion
// 2 = power down
settings.mag.operatingMode = 0;
settings.temp.enabled = TRUE;
for (int i=0; i<3; i++)
{
gBias[i] = 0;
aBias[i] = 0;
mBias[i] = 0;
gBiasRaw[i] = 0;
aBiasRaw[i] = 0;
mBiasRaw[i] = 0;
}
_autoCalc = FALSE;
}
uint16_t begin(void)
{
//! Todo: don't use _xgAddress or _mAddress, duplicating memory
_xgAddress = settings.device.agAddress;
_mAddress = settings.device.mAddress;
constrainScales();
// Once we have the scale values, we can calculate the resolution
// of each sensor. That's what these functions are for. One for each sensor
calcgRes(); // Calculate DPS / ADC tick, stored in gRes variable
calcmRes(); // Calculate Gs / ADC tick, stored in mRes variable
calcaRes(); // Calculate g / ADC tick, stored in aRes variable
if (settings.device.commInterface == IMU_MODE_I2C) // If we're using I2C
initI2C(); // Initialize I2C
else if (settings.device.commInterface == IMU_MODE_SPI) // else, if we're using SPI
initSPI(); // Initialize SPI
// To verify communication, we can read from the WHO_AM_I register of
// each device. Store those in a variable so we can return them.
uint8_t mTest = mReadByte(WHO_AM_I_M); // Read the gyro WHO_AM_I
delay(DELAY * 150);
uint8_t xgTest = xgReadByte(WHO_AM_I_XG); // Read the accel/mag WHO_AM_I
uint16_t whoAmICombined = (xgTest << 8) | mTest;
if (whoAmICombined != ((WHO_AM_I_AG_RSP << 8) | WHO_AM_I_M_RSP))
{
return 0;
}
// Gyro initialization stuff:
initGyro(); // This will "turn on" the gyro. Setting up interrupts, etc.
// Accelerometer initialization stuff:
initAccel(); // "Turn on" all axes of the accel. Set up interrupts, etc.
// Magnetometer initialization stuff:
initMag(); // "Turn on" all axes of the mag. Set up interrupts, etc.
// Once everything is initialized, return the WHO_AM_I registers we read:
return whoAmICombined;
}
void constrainScales()
{
if ((settings.gyro.scale != 245) && (settings.gyro.scale != 500) && (settings.gyro.scale != 2000))
{
settings.gyro.scale = 245;
}
if ((settings.accel.scale != 2) && (settings.accel.scale != 4) && (settings.accel.scale != 8) && (settings.accel.scale != 16))
{
settings.accel.scale = 2;
}
if ((settings.mag.scale != 4) && (settings.mag.scale != 8) && (settings.mag.scale != 12) && (settings.mag.scale != 16))
{
settings.mag.scale = 4;
}
}
void initI2C(void)
{
;
}
void initSPI(void)
{
;
}
void calcgRes()
{
gRes = ((float) settings.gyro.scale) / 32768.0;
}
void calcaRes()
{
aRes = ((float) settings.accel.scale) / 32768.0;
}
void calcmRes()
{
//mRes = ((float) settings.mag.scale) / 32768.0;
switch (settings.mag.scale)
{
case 4:
mRes = magSensitivity[0];
break;
case 8:
mRes = magSensitivity[1];
break;
case 12:
mRes = magSensitivity[2];
break;
case 16:
mRes = magSensitivity[3];
break;
}
}
void delay(int d)
{
for(int i = 0; i < d; i++) i++;
}
uint8_t I2CreadByte(uint8_t address, uint8_t subAddress)
{
uint32_t stageOfReading = 0;
//deviceAddress address = *((deviceAddress*)T);
I2C001_DataType data1;
data1.Data1.TDF_Type = I2C_TDF_MStart;
data1.Data1.Data = ((address<<1) | I2C_WRITE);
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data1);/*);*/
delay(DELAY*10);
I2C001_DataType data2;
data2.Data1.TDF_Type = I2C_TDF_MTxData;
data2.Data1.Data = subAddress;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data2);/*);*/
delay(DELAY*10);
//delay(15000);
I2C001_DataType data3;
data3.Data1.TDF_Type = I2C_TDF_MRStart;
data3.Data1.Data = ((address<<1) | I2C_READ);
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data3);/*);*/
delay(DELAY*10);
I2C001_DataType data4;
data4.Data1.TDF_Type = I2C_TDF_MRxAck1;
data4.Data1.Data = ubyteFF;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data4);/*);*/
/*while (!(I2C001_SET == I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_RIF)))
{
int i = 0;
if(I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_NACK_RECEIVED))
{
break;
}
};*/
delay(DELAY);
I2C001_DataType data5;
data5.Data1.TDF_Type = I2C_TDF_MStop;
data5.Data1.Data = ubyteFF;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data5);/*);*/
stageOfReading++;
int k = 0;
while(0 == received){k++; if(k > 4000) break; }
received = 0;
delay(DELAY*10);
int j = USIC_GetRxFIFOFillingLevel(I2C001_Handle0.I2CRegs);
//uint16_t DataReceive1 = 0;
//(USIC_ubIsRxFIFOempty(I2C001_Handle0.I2CRegs)){};
//delay(15000);
/*while(I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_SRBI) ==
I2C001_RESET)
{
int i = 0;
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RIF);
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RSIF);
}
while(USIC_ubIsRxFIFOempty(I2C001_Handle0.I2CRegs));
I2C001_ReadData(&I2C001_Handle0,&DataReceive1);
int j = USIC_GetRxFIFOFillingLevel(I2C001_Handle0.I2CRegs);*/
//I2C001_Handle0.I2CRegs->TRBSCR;
/*while(I2C001_SET == I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_RIF))
{
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RIF);
}
while(I2C001_SET == I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_RSIF))
{
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RSIF);
}
while(I2C001_SET == I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_DLIF))
{
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_DLIF);
}
while(I2C001_SET == I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_RBERI))
{
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RBERI);
}*/
//I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RSIF);
/*uint16_t DataReceive1 = 0;
while (!I2C001_GetFlagStatus(&I2C001_Handle0, I2C001_FLAG_RIF));
if(I2C001_ReadData(&I2C001_Handle0,&DataReceive1))
{
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RIF);
I2C001_ClearFlag(&I2C001_Handle0, I2C001_FLAG_RSIF);
stageOfReading++;
delay(DELAY);
}
else
{
stageOfReading--;
}*/
return (uint8_t)DataReceive1;
}
void FIFO_Receive_Int_Handler(void)
{
/*uint16_t */DataReceive1 = 0;
I2C001_ReadData(&I2C001_Handle0,&DataReceive1);
//delay(10000);
received = 1;
}
void IIC_Prot_Int_Handler(void)
{
I2C001_Handle0.I2CRegs->FMR = 0x00000002U << USIC_CH_FMR_MTDV_Pos; // clear TDV and TE
I2C001_Handle0.I2CRegs->TRBSCR = USIC_CH_TRBSCR_FLUSHTB_Msk; // flush FIFO transmit buffer
I2C001_Handle0.I2CRegs->PSCR |= USIC_CH_PSCR_CST5_Msk; // clear PSR.NACK flag
IO004_ResetPin(IO004_Handle0);
}
uint8_t mReadByte(uint8_t subAddress)
{
// Whether we're using I2C or SPI, read a byte using the
// accelerometer-specific I2C address or SPI CS pin.
if (settings.device.commInterface == IMU_MODE_I2C)
return I2CreadByte(_mAddress, subAddress);
/*else if (settings.device.commInterface == IMU_MODE_SPI)
return SPIreadByte(_mAddress, subAddress);*/
}
uint8_t xgReadByte(uint8_t subAddress)
{
// Whether we're using I2C or SPI, read a byte using the
// gyro-specific I2C address or SPI CS pin.
if (settings.device.commInterface == IMU_MODE_I2C)
return I2CreadByte(_xgAddress, subAddress);
/*else if (settings.device.commInterface == IMU_MODE_SPI)
return SPIreadByte(_xgAddress, subAddress);*/
}
void initGyro(void)
{
uint8_t tempRegValue = 0;
// CTRL_REG1_G (Default value: 0x00)
// [ODR_G2][ODR_G1][ODR_G0][FS_G1][FS_G0][0][BW_G1][BW_G0]
// ODR_G[2:0] - Output data rate selection
// FS_G[1:0] - Gyroscope full-scale selection
// BW_G[1:0] - Gyroscope bandwidth selection
// To disable gyro, set sample rate bits to 0. We'll only set sample
// rate if the gyro is enabled.
if (settings.gyro.enabled)
{
tempRegValue = (settings.gyro.sampleRate & 0x07) << 5;
}
switch (settings.gyro.scale)
{
case 500:
tempRegValue |= (0x1 << 3);
break;
case 2000:
tempRegValue |= (0x3 << 3);
break;
// Otherwise we'll set it to 245 dps (0x0 << 4)
}
tempRegValue |= (settings.gyro.bandwidth & 0x3);
xgWriteByte(CTRL_REG1_G, tempRegValue);
// CTRL_REG2_G (Default value: 0x00)
// [0][0][0][0][INT_SEL1][INT_SEL0][OUT_SEL1][OUT_SEL0]
// INT_SEL[1:0] - INT selection configuration
// OUT_SEL[1:0] - Out selection configuration
xgWriteByte(CTRL_REG2_G, 0x00);
// CTRL_REG3_G (Default value: 0x00)
// [LP_mode][HP_EN][0][0][HPCF3_G][HPCF2_G][HPCF1_G][HPCF0_G]
// LP_mode - Low-power mode enable (0: disabled, 1: enabled)
// HP_EN - HPF enable (0:disabled, 1: enabled)
// HPCF_G[3:0] - HPF cutoff frequency
tempRegValue = settings.gyro.lowPowerEnable ? (1<<7) : 0;
if (settings.gyro.HPFEnable)
{
tempRegValue |= ((1<<6) | (settings.gyro.HPFCutoff & 0x0F));
}
xgWriteByte(CTRL_REG3_G, tempRegValue);
// CTRL_REG4 (Default value: 0x38)
// [0][0][Zen_G][Yen_G][Xen_G][0][LIR_XL1][4D_XL1]
// Zen_G - Z-axis output enable (0:disable, 1:enable)
// Yen_G - Y-axis output enable (0:disable, 1:enable)
// Xen_G - X-axis output enable (0:disable, 1:enable)
// LIR_XL1 - Latched interrupt (0:not latched, 1:latched)
// 4D_XL1 - 4D option on interrupt (0:6D used, 1:4D used)
tempRegValue = 0;
if (settings.gyro.enableZ) tempRegValue |= (1<<5);
if (settings.gyro.enableY) tempRegValue |= (1<<4);
if (settings.gyro.enableX) tempRegValue |= (1<<3);
if (settings.gyro.latchInterrupt) tempRegValue |= (1<<1);
xgWriteByte(CTRL_REG4, tempRegValue);
// ORIENT_CFG_G (Default value: 0x00)
// [0][0][SignX_G][SignY_G][SignZ_G][Orient_2][Orient_1][Orient_0]
// SignX_G - Pitch axis (X) angular rate sign (0: positive, 1: negative)
// Orient [2:0] - Directional user orientation selection
tempRegValue = 0;
if (settings.gyro.flipX) tempRegValue |= (1<<5);
if (settings.gyro.flipY) tempRegValue |= (1<<4);
if (settings.gyro.flipZ) tempRegValue |= (1<<3);
xgWriteByte(ORIENT_CFG_G, tempRegValue);
}
void xgWriteByte(uint8_t subAddress, uint8_t data)
{
// Whether we're using I2C or SPI, write a byte using the
// gyro-specific I2C address or SPI CS pin.
if (settings.device.commInterface == IMU_MODE_I2C)
{
I2CwriteByte(_xgAddress, subAddress, data);
}
}
void I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data)
{
uint8_t c = (address<<1);
I2C001_DataType data1;
data1.Data1.TDF_Type = I2C_TDF_MStart;
data1.Data1.Data = (c | I2C_WRITE);
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data1);/*);*/
delay(DELAY);
I2C001_DataType data2;
data2.Data1.TDF_Type = I2C_TDF_MTxData;
data2.Data1.Data = subAddress;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data2);/*);*/
delay(DELAY);
I2C001_DataType data3;
data3.Data1.TDF_Type = I2C_TDF_MTxData;
data3.Data1.Data = data;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data3);/*);*/
delay(DELAY);
I2C001_DataType data4;
data4.Data1.TDF_Type = I2C_TDF_MStop;
data4.Data1.Data = ubyteFF;
/*while(!*/I2C001_WriteData(&I2C001_Handle0,&data4);/*);*/
delay(DELAY * 100);
}
void initAccel(void)
{
uint8_t tempRegValue = 0;
// CTRL_REG5_XL (0x1F) (Default value: 0x38)
// [DEC_1][DEC_0][Zen_XL][Yen_XL][Zen_XL][0][0][0]
// DEC[0:1] - Decimation of accel data on OUT REG and FIFO.
// 00: None, 01: 2 samples, 10: 4 samples 11: 8 samples
// Zen_XL - Z-axis output enabled
// Yen_XL - Y-axis output enabled
// Xen_XL - X-axis output enabled
if (settings.accel.enableZ) tempRegValue |= (1<<5);
if (settings.accel.enableY) tempRegValue |= (1<<4);
if (settings.accel.enableX) tempRegValue |= (1<<3);
xgWriteByte(CTRL_REG5_XL, tempRegValue);
// CTRL_REG6_XL (0x20) (Default value: 0x00)
// [ODR_XL2][ODR_XL1][ODR_XL0][FS1_XL][FS0_XL][BW_SCAL_ODR][BW_XL1][BW_XL0]
// ODR_XL[2:0] - Output data rate & power mode selection
// FS_XL[1:0] - Full-scale selection
// BW_SCAL_ODR - Bandwidth selection
// BW_XL[1:0] - Anti-aliasing filter bandwidth selection
tempRegValue = 0;
// To disable the accel, set the sampleRate bits to 0.
if (settings.accel.enabled)
{
tempRegValue |= ((settings.accel.sampleRate & 0x07) << 5);
}
switch (settings.accel.scale)
{
case 4:
tempRegValue |= (0x2 << 3);
break;
case 8:
tempRegValue |= (0x3 << 3);
break;
case 16:
tempRegValue |= (0x1 << 3);
break;
// Otherwise it'll be set to 2g (0x0 << 3)
}
if (settings.accel.bandwidth >= 0)
{
tempRegValue |= (1<<2); // Set BW_SCAL_ODR
tempRegValue |= (settings.accel.bandwidth & 0x03);
}
xgWriteByte(CTRL_REG6_XL, tempRegValue);
// CTRL_REG7_XL (0x21) (Default value: 0x00)
// [HR][DCF1][DCF0][0][0][FDS][0][HPIS1]
// HR - High resolution mode (0: disable, 1: enable)
// DCF[1:0] - Digital filter cutoff frequency
// FDS - Filtered data selection
// HPIS1 - HPF enabled for interrupt function
tempRegValue = 0;
if (settings.accel.highResEnable)
{
tempRegValue |= (1<<7); // Set HR bit
tempRegValue |= (settings.accel.highResBandwidth & 0x3) << 5;
}
xgWriteByte(CTRL_REG7_XL, tempRegValue);
}
void initMag(void)
{
uint8_t tempRegValue = 0;
// CTRL_REG1_M (Default value: 0x10)
// [TEMP_COMP][OM1][OM0][DO2][DO1][DO0][0][ST]
// TEMP_COMP - Temperature compensation
// OM[1:0] - X & Y axes op mode selection
// 00:low-power, 01:medium performance
// 10: high performance, 11:ultra-high performance
// DO[2:0] - Output data rate selection
// ST - Self-test enable
if (settings.mag.tempCompensationEnable) tempRegValue |= (1<<7);
tempRegValue |= (settings.mag.XYPerformance & 0x3) << 5;
tempRegValue |= (settings.mag.sampleRate & 0x7) << 2;
mWriteByte(CTRL_REG1_M, tempRegValue);
// CTRL_REG2_M (Default value 0x00)
// [0][FS1][FS0][0][REBOOT][SOFT_RST][0][0]
// FS[1:0] - Full-scale configuration
// REBOOT - Reboot memory content (0:normal, 1:reboot)
// SOFT_RST - Reset config and user registers (0:default, 1:reset)
tempRegValue = 0;
switch (settings.mag.scale)
{
case 8:
tempRegValue |= (0x1 << 5);
break;
case 12:
tempRegValue |= (0x2 << 5);
break;
case 16:
tempRegValue |= (0x3 << 5);
break;
// Otherwise we'll default to 4 gauss (00)
}
mWriteByte(CTRL_REG2_M, tempRegValue); // +/-4Gauss
// CTRL_REG3_M (Default value: 0x03)
// [I2C_DISABLE][0][LP][0][0][SIM][MD1][MD0]
// I2C_DISABLE - Disable I2C interace (0:enable, 1:disable)
// LP - Low-power mode cofiguration (1:enable)
// SIM - SPI mode selection (0:write-only, 1:read/write enable)
// MD[1:0] - Operating mode
// 00:continuous conversion, 01:single-conversion,
// 10,11: Power-down
tempRegValue = 0;
if (settings.mag.lowPowerEnable) tempRegValue |= (1<<5);
tempRegValue |= (settings.mag.operatingMode & 0x3);
mWriteByte(CTRL_REG3_M, tempRegValue); // Continuous conversion mode
// CTRL_REG4_M (Default value: 0x00)
// [0][0][0][0][OMZ1][OMZ0][BLE][0]
// OMZ[1:0] - Z-axis operative mode selection
// 00:low-power mode, 01:medium performance
// 10:high performance, 10:ultra-high performance
// BLE - Big/little endian data
tempRegValue = 0;
tempRegValue = (settings.mag.ZPerformance & 0x3) << 2;
mWriteByte(CTRL_REG4_M, tempRegValue);
// CTRL_REG5_M (Default value: 0x00)
// [0][BDU][0][0][0][0][0][0]
// BDU - Block data update for magnetic data
// 0:continuous, 1:not updated until MSB/LSB are read
tempRegValue = 0;
mWriteByte(CTRL_REG5_M, tempRegValue);
}
void mWriteByte(uint8_t subAddress, uint8_t data)
{
// Whether we're using I2C or SPI, write a byte using the
// accelerometer-specific I2C address or SPI CS pin.
if (settings.device.commInterface == IMU_MODE_I2C)
{
return I2CwriteByte(_mAddress, subAddress, data);
}
}
void enableFIFO(bool enable)
{
uint8_t temp = xgReadByte(CTRL_REG9);
if(enable)
{
temp |= (1<<1);
}
else
{
temp &= ~(1<<1);
}
xgWriteByte(CTRL_REG9, temp);
}
void setFIFO(fifoMode_type fifoMode, uint8_t fifoThs)
{
// Limit threshold - 0x1F (31) is the maximum. If more than that was asked
// limit it to the maximum.
uint8_t threshold = fifoThs <= 0x1F ? fifoThs : 0x1F;
xgWriteByte(FIFO_CTRL, ((fifoMode & 0x7) << 5) | (threshold & 0x1F));
}
void calibrate(bool autoCalc)
{
uint8_t data[6] = {0, 0, 0, 0, 0, 0};
uint8_t samples = 0;
int ii;
int32_t aBiasRawTemp[3] = {0, 0, 0};
int32_t gBiasRawTemp[3] = {0, 0, 0};
// Turn on FIFO and set threshold to 32 samples
enableFIFO(TRUE);
setFIFO(FIFO_THS, 0x1F);
/*while (samples < 29)
{*/
samples = (xgReadByte(FIFO_SRC) & 0x3F); // Read number of stored samples
//samples = 10;
//}
for(ii = 0; ii < samples ; ii++)
{ // Read the gyro data stored in the FIFO
readGyro1();
gBiasRawTemp[0] += gx;
gBiasRawTemp[1] += gy;
gBiasRawTemp[2] += gz;
readAccel1();