Skip to content

Commit 6a71121

Browse files
committed
add fifo timestamp
1 parent ad1e9c4 commit 6a71121

File tree

3 files changed

+179
-12
lines changed

3 files changed

+179
-12
lines changed

LSM6DS3.cpp

Lines changed: 48 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ status_t LSM6DS3Core::beginCore(void) {
9898
#elif defined(ARDUINO_XIAO_MG24)
9999
// SPI.setClockDivider(SPI_CLOCK_DIV4);
100100
SPI.setClockDivider(4);
101-
#endif
101+
#endif
102102
// Data is read and written MSb first.
103103
#ifdef ESP32
104104
SPI.setBitOrder(SPI_MSBFIRST);
@@ -171,7 +171,7 @@ status_t LSM6DS3Core::readRegisterRegion(uint8_t* outputPointer, uint8_t offset,
171171
//define pointer that will point to the external space
172172
uint8_t i = 0;
173173
uint8_t c = 0;
174-
#ifndef TARGET_SEEED_XIAO_NRF52840_SENSE
174+
#ifndef TARGET_SEEED_XIAO_NRF52840_SENSE
175175
uint8_t tempFFCounter = 0;
176176
#endif
177177
switch (commInterface) {
@@ -393,7 +393,6 @@ LSM6DS3::LSM6DS3(uint8_t busType, uint8_t inputArg) : LSM6DS3Core(busType, input
393393

394394
allOnesCounter = 0;
395395
nonSuccessCounter = 0;
396-
397396
}
398397

399398
//****************************************************************************//
@@ -570,6 +569,14 @@ status_t LSM6DS3::begin() {
570569
}
571570
}
572571

572+
if (settings.timestampEnabled) {
573+
// Enable the timestamp counter (CTRL10_C寄存器)
574+
uint8_t ctrl10_c;
575+
readRegister(&ctrl10_c, LSM6DS3_ACC_GYRO_CTRL10_C);
576+
ctrl10_c |= 0x20; // set TIMER_EN
577+
writeRegister(LSM6DS3_ACC_GYRO_CTRL10_C, ctrl10_c);
578+
}
579+
573580
return returnError;
574581
}
575582

@@ -728,6 +735,20 @@ float LSM6DS3::readTempF(void) {
728735

729736
}
730737

738+
//****************************************************************************//
739+
//
740+
// Timestamp section
741+
//
742+
//****************************************************************************//
743+
uint32_t LSM6DS3::fifoTimestamp() {
744+
uint8_t data[6];
745+
status_t error = readRegisterRegion(data, LSM6DS3_ACC_GYRO_FIFO_DATA_OUT_L, 3*sizeof(uint16_t));
746+
if (error == IMU_SUCCESS) {
747+
return (data[1] << 16) | (data[0] << 8) | data[3];
748+
}
749+
return 0;
750+
}
751+
731752
//****************************************************************************//
732753
//
733754
// FIFO section
@@ -761,8 +782,28 @@ void LSM6DS3::fifoBegin(void) {
761782
tempFIFO_CTRL3 |= (settings.accelFifoDecimation & 0x07);
762783
}
763784

764-
//CONFIGURE FIFO_CTRL4 (nothing for now-- sets data sets 3 and 4
765-
uint8_t tempFIFO_CTRL4 = 0;
785+
if (settings.timestampFifoEnabled == 1) {
786+
// Write timestamp data to the FIFO.
787+
uint8_t fifo_ctrl2;
788+
readRegister(&fifo_ctrl2, LSM6DS3_ACC_GYRO_FIFO_CTRL2);
789+
fifo_ctrl2 |= 0x80; // FIFO_CTRL2(07H)->TIMER_PEDO_FIFO_EN
790+
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL2, fifo_ctrl2);
791+
792+
// translates to "Set timestamp resolution
793+
uint8_t tap_cfg;
794+
readRegister(&tap_cfg, LSM6DS3_ACC_GYRO_WAKE_UP_DUR);
795+
tap_cfg &= ~(1 << 4);
796+
// timestampResolution
797+
// 0: 6.4ms
798+
// 1: 25us
799+
tap_cfg |= (settings.timestampResolution & 0x01) << 4;
800+
writeRegister(LSM6DS3_ACC_GYRO_WAKE_UP_DUR, tap_cfg);
801+
}
802+
803+
// CONFIGURE FIFO_CTRL4
804+
// Select the decimation factor for the 4th FIFO dataset by configuring the DEC_DS4_FIFO[2:0] field in the FIFO_CTRL4 register.
805+
//If you don't need the third and fourth datasets, this value can be set to 0
806+
uint8_t tempFIFO_CTRL4 = 0x09;
766807

767808

768809
//CONFIGURE FIFO_CTRL5
@@ -805,13 +846,10 @@ void LSM6DS3::fifoBegin(void) {
805846

806847
//Write the data
807848
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL1, thresholdLByte);
808-
//Serial.println(thresholdLByte, HEX);
809-
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL2, thresholdHByte);
810-
//Serial.println(thresholdHByte, HEX);
849+
//writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL2, thresholdHByte);
811850
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL3, tempFIFO_CTRL3);
812851
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL4, tempFIFO_CTRL4);
813852
writeRegister(LSM6DS3_ACC_GYRO_FIFO_CTRL5, tempFIFO_CTRL5);
814-
815853
}
816854
void LSM6DS3::fifoClear(void) {
817855
//Drain the fifo data and dump it
@@ -847,5 +885,4 @@ uint16_t LSM6DS3::fifoGetStatus(void) {
847885
void LSM6DS3::fifoEnd(void) {
848886
// turn off the fifo
849887
writeRegister(LSM6DS3_ACC_GYRO_FIFO_STATUS1, 0x00); //Disable
850-
}
851-
888+
}

LSM6DS3.h

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#ifndef __LSM6DS3IMU_H__
2828
#define __LSM6DS3IMU_H__
2929

30+
#include "Arduino.h"
3031
#include "stdint.h"
3132

3233
#define I2C_MODE 0
@@ -122,6 +123,9 @@ struct SensorSettings {
122123

123124
uint16_t tempSensitivity;
124125

126+
uint8_t timestampEnabled; // Enable timestamp feature
127+
uint8_t timestampFifoEnabled; // write timestamp data in FIFO
128+
uint8_t timestampResolution; // Set timestamp resolution ; 0: 6.4ms 1: 25us
125129
};
126130

127131

@@ -179,6 +183,7 @@ class LSM6DS3 : public LSM6DS3Core {
179183
float calcGyro(int16_t);
180184
float calcAccel(int16_t);
181185

186+
uint32_t fifoTimestamp(void);
182187
private:
183188

184189
};
@@ -2084,4 +2089,4 @@ typedef enum {
20842089
LSM6DS3_ACC_GYRO_INT2_SLEEP_ENABLED = 0x80,
20852090
} LSM6DS3_ACC_GYRO_INT2_SLEEP_t;
20862091

2087-
#endif // End of __LSM6DS3IMU_H__ definition check
2092+
#endif // End of __LSM6DS3IMU_H__ definition check
Lines changed: 125 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,125 @@
1+
#include <LSM6DS3.h>
2+
#include <Wire.h>
3+
4+
//Create a instance of class LSM6DS3
5+
LSM6DS3 myIMU(I2C_MODE, 0x6A); //I2C device address 0x6A
6+
7+
void setup( void ) {
8+
//Over-ride default settings if desired
9+
myIMU.settings.gyroEnabled = 1; //Can be 0 or 1
10+
myIMU.settings.gyroRange = 2000; //Max deg/s. Can be: 125, 245, 500, 1000, 2000
11+
myIMU.settings.gyroSampleRate = 833; //Hz. Can be: 13, 26, 52, 104, 208, 416, 833, 1666
12+
myIMU.settings.gyroBandWidth = 200; //Hz. Can be: 50, 100, 200, 400;
13+
myIMU.settings.gyroFifoEnabled = 1; //Set to include gyro in FIFO
14+
myIMU.settings.gyroFifoDecimation = 1; //set 1 for on /1
15+
16+
myIMU.settings.accelEnabled = 1;
17+
myIMU.settings.accelRange = 16; //Max G force readable. Can be: 2, 4, 8, 16
18+
myIMU.settings.accelSampleRate = 833; //Hz. Can be: 13, 26, 52, 104, 208, 416, 833, 1666, 3332, 6664, 13330
19+
myIMU.settings.accelBandWidth = 200; //Hz. Can be: 50, 100, 200, 400;
20+
myIMU.settings.accelFifoEnabled = 1; //Set to include accelerometer in the FIFO
21+
myIMU.settings.accelFifoDecimation = 1; //set 1 for on /1
22+
myIMU.settings.tempEnabled = 1;
23+
24+
//Non-basic mode settings
25+
myIMU.settings.commMode = 1;
26+
27+
myIMU.settings.timestampEnabled=1; // 1: enable timestamp ; 0: disable timestamp
28+
myIMU.settings.timestampFifoEnabled=1;// 1: enable write timestamp into fifo ; 0: disable
29+
myIMU.settings.timestampResolution=1; // 1: Set timestamp resolution ; 0: 6.4ms 1: 25us
30+
31+
//FIFO control settings
32+
myIMU.settings.fifoThreshold = 100; //Can be 0 to 4096 (16 bit bytes)
33+
myIMU.settings.fifoSampleRate = 50; //Hz. Can be: 10, 25, 50, 100, 200, 400, 800, 1600, 3300, 6600
34+
myIMU.settings.fifoModeWord = 6; //FIFO mode.
35+
//FIFO mode. Can be:
36+
// 0 (Bypass mode, FIFO off)
37+
// 1 (Stop when full)
38+
// 3 (Continuous during trigger)
39+
// 4 (Bypass until trigger)
40+
// 6 (Continous mode)
41+
42+
43+
Serial.begin(57600); // start serial for output
44+
delay(1000); //relax...
45+
Serial.println("Processor came out of reset.\n");
46+
47+
//Call .begin() to configure the IMUs
48+
if( myIMU.begin() != 0 )
49+
{
50+
Serial.println("Problem starting the sensor with CS @ Pin 10.");
51+
}
52+
else
53+
{
54+
Serial.println("Sensor with CS @ Pin 10 started.");
55+
}
56+
57+
Serial.print("Configuring FIFO with no error checking...");
58+
myIMU.fifoBegin();
59+
Serial.print("Done!\n");
60+
61+
Serial.print("Clearing out the FIFO...");
62+
myIMU.fifoClear();
63+
Serial.print("Done!\n");
64+
65+
}
66+
67+
68+
void loop()
69+
{
70+
float temp; //This is to hold read data
71+
uint16_t tempUnsigned;
72+
73+
while( ( myIMU.fifoGetStatus() & 0x8000 ) == 0 ) {}; //Wait for watermark
74+
75+
//Now loop until FIFO is empty. NOTE: As the FIFO is only 8 bits wide,
76+
//the channels must be synchronized to a known position for the data to align
77+
//properly. Emptying the fifo is one way of doing this (this example)
78+
while( ( myIMU.fifoGetStatus() & 0x1000 ) == 0 ) {
79+
80+
temp = myIMU.calcGyro(myIMU.fifoRead());
81+
Serial.print(temp);
82+
Serial.print(",");
83+
84+
temp = myIMU.calcGyro(myIMU.fifoRead());
85+
Serial.print(temp);
86+
Serial.print(",");
87+
88+
temp = myIMU.calcGyro(myIMU.fifoRead());
89+
Serial.print(temp);
90+
Serial.print(",");
91+
92+
temp = myIMU.calcAccel(myIMU.fifoRead());
93+
Serial.print(temp);
94+
Serial.print(",");
95+
96+
temp = myIMU.calcAccel(myIMU.fifoRead());
97+
Serial.print(temp);
98+
Serial.print(",");
99+
100+
temp = myIMU.calcAccel(myIMU.fifoRead());
101+
Serial.print(temp);
102+
103+
// The third dataset corresponds to external sensor data.
104+
// You need to read the third dataset first before you can read the timestamp data.
105+
// Therefore, you can ignore this dataset.
106+
uint16_t thirdData = myIMU.fifoTimestamp();
107+
108+
// The third dataset
109+
// timestamp in fifo
110+
uint32_t fifoTimestamp = myIMU.fifoTimestamp();
111+
Serial.print(",");
112+
Serial.print("FIFO time: ");
113+
Serial.print(fifoTimestamp);
114+
Serial.print("\n");
115+
116+
delay(10); //Wait for the serial buffer to clear (~50 bytes worth of time @ 57600baud)
117+
118+
}
119+
120+
tempUnsigned = myIMU.fifoGetStatus();
121+
Serial.print("\nFifo Status 1 and 2 (16 bits): 0x");
122+
Serial.println(tempUnsigned, HEX);
123+
Serial.print("\n");
124+
125+
}

0 commit comments

Comments
 (0)