IMU driver (this thing is a mess).
Dependents: PM2_Libary PM2_Libary
LSM9DS1_i2c.cpp@0:211f27847e85, 2022-02-23 (annotated)
- Committer:
- pmic
- Date:
- Wed Feb 23 07:16:58 2022 +0000
- Revision:
- 0:211f27847e85
Included driver for LSM9DS1 IMU.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
pmic | 0:211f27847e85 | 1 | /****************************************************************************** |
pmic | 0:211f27847e85 | 2 | SFE_LSM9DS1.cpp |
pmic | 0:211f27847e85 | 3 | SFE_LSM9DS1 Library Source File |
pmic | 0:211f27847e85 | 4 | Jim Lindblom @ SparkFun Electronics |
pmic | 0:211f27847e85 | 5 | Original Creation Date: February 27, 2015 |
pmic | 0:211f27847e85 | 6 | https://github.com/sparkfun/LSM9DS1_Breakout |
pmic | 0:211f27847e85 | 7 | |
pmic | 0:211f27847e85 | 8 | This file implements all functions of the LSM9DS1 class. Functions here range |
pmic | 0:211f27847e85 | 9 | from higher level stuff, like reading/writing LSM9DS1 registers to low-level, |
pmic | 0:211f27847e85 | 10 | hardware reads and writes. Both SPI and I2C handler functions can be found |
pmic | 0:211f27847e85 | 11 | towards the bottom of this file. |
pmic | 0:211f27847e85 | 12 | |
pmic | 0:211f27847e85 | 13 | Development environment specifics: |
pmic | 0:211f27847e85 | 14 | IDE: Arduino 1.6 |
pmic | 0:211f27847e85 | 15 | Hardware Platform: Arduino Uno |
pmic | 0:211f27847e85 | 16 | LSM9DS1 Breakout Version: 1.0 |
pmic | 0:211f27847e85 | 17 | |
pmic | 0:211f27847e85 | 18 | This code is beerware; if you see me (or any other SparkFun employee) at the |
pmic | 0:211f27847e85 | 19 | local, and you've found our code helpful, please buy us a round! |
pmic | 0:211f27847e85 | 20 | |
pmic | 0:211f27847e85 | 21 | Distributed as-is; no warranty is given. |
pmic | 0:211f27847e85 | 22 | |
pmic | 0:211f27847e85 | 23 | Modified: Nicolas Borla, 20.01.2019 |
pmic | 0:211f27847e85 | 24 | ******************************************************************************/ |
pmic | 0:211f27847e85 | 25 | |
pmic | 0:211f27847e85 | 26 | #include "LSM9DS1_i2c.h" |
pmic | 0:211f27847e85 | 27 | #include "LSM9DS1_Registers.h" |
pmic | 0:211f27847e85 | 28 | #include "LSM9DS1_Types.h" |
pmic | 0:211f27847e85 | 29 | //#include <Wire.h> // Wire library is used for I2C |
pmic | 0:211f27847e85 | 30 | //#include <SPI.h> // SPI library is used for...SPI. |
pmic | 0:211f27847e85 | 31 | |
pmic | 0:211f27847e85 | 32 | //#if defined(ARDUINO) && ARDUINO >= 100 |
pmic | 0:211f27847e85 | 33 | // #include "Arduino.h" |
pmic | 0:211f27847e85 | 34 | //#else |
pmic | 0:211f27847e85 | 35 | // #include "WProgram.h" |
pmic | 0:211f27847e85 | 36 | //#endif |
pmic | 0:211f27847e85 | 37 | |
pmic | 0:211f27847e85 | 38 | #define LSM9DS1_COMMUNICATION_TIMEOUT 1000 |
pmic | 0:211f27847e85 | 39 | |
pmic | 0:211f27847e85 | 40 | float magSensitivity[4] = {0.00014, 0.00029, 0.00043, 0.00058}; |
pmic | 0:211f27847e85 | 41 | //extern Serial pc; |
pmic | 0:211f27847e85 | 42 | |
pmic | 0:211f27847e85 | 43 | LSM9DS1::LSM9DS1(PinName sda, PinName scl, uint8_t xgAddr, uint8_t mAddr) |
pmic | 0:211f27847e85 | 44 | :i2c(sda, scl) |
pmic | 0:211f27847e85 | 45 | { |
pmic | 0:211f27847e85 | 46 | init(IMU_MODE_I2C, xgAddr, mAddr); // dont know about 0xD6 or 0x3B |
pmic | 0:211f27847e85 | 47 | begin(); |
pmic | 0:211f27847e85 | 48 | } |
pmic | 0:211f27847e85 | 49 | |
pmic | 0:211f27847e85 | 50 | LSM9DS1::LSM9DS1(PinName sda, PinName scl) |
pmic | 0:211f27847e85 | 51 | :i2c(sda, scl) |
pmic | 0:211f27847e85 | 52 | { |
pmic | 0:211f27847e85 | 53 | init(IMU_MODE_I2C, 0xD6, 0x3C); // dont know about 0xD6 or 0x3B |
pmic | 0:211f27847e85 | 54 | begin(); |
pmic | 0:211f27847e85 | 55 | } |
pmic | 0:211f27847e85 | 56 | |
pmic | 0:211f27847e85 | 57 | /* |
pmic | 0:211f27847e85 | 58 | LSM9DS1::LSM9DS1() |
pmic | 0:211f27847e85 | 59 | { |
pmic | 0:211f27847e85 | 60 | init(IMU_MODE_I2C, LSM9DS1_AG_ADDR(1), LSM9DS1_M_ADDR(1)); |
pmic | 0:211f27847e85 | 61 | } |
pmic | 0:211f27847e85 | 62 | |
pmic | 0:211f27847e85 | 63 | LSM9DS1::LSM9DS1(interface_mode interface, uint8_t xgAddr, uint8_t mAddr) |
pmic | 0:211f27847e85 | 64 | { |
pmic | 0:211f27847e85 | 65 | init(interface, xgAddr, mAddr); |
pmic | 0:211f27847e85 | 66 | } |
pmic | 0:211f27847e85 | 67 | */ |
pmic | 0:211f27847e85 | 68 | |
pmic | 0:211f27847e85 | 69 | void LSM9DS1::init(interface_mode interface, uint8_t xgAddr, uint8_t mAddr) |
pmic | 0:211f27847e85 | 70 | { |
pmic | 0:211f27847e85 | 71 | settings.device.commInterface = interface; |
pmic | 0:211f27847e85 | 72 | settings.device.agAddress = xgAddr; |
pmic | 0:211f27847e85 | 73 | settings.device.mAddress = mAddr; |
pmic | 0:211f27847e85 | 74 | |
pmic | 0:211f27847e85 | 75 | settings.gyro.enabled = true; |
pmic | 0:211f27847e85 | 76 | settings.gyro.enableX = true; |
pmic | 0:211f27847e85 | 77 | settings.gyro.enableY = true; |
pmic | 0:211f27847e85 | 78 | settings.gyro.enableZ = true; |
pmic | 0:211f27847e85 | 79 | // gyro scale can be 245, 500, or 2000 dps (degree per second) |
pmic | 0:211f27847e85 | 80 | settings.gyro.scale = 500; |
pmic | 0:211f27847e85 | 81 | // gyro sample rate: value between 1-6 in Hz |
pmic | 0:211f27847e85 | 82 | // 1 = 14.9 4 = 238 |
pmic | 0:211f27847e85 | 83 | // 2 = 59.5 5 = 476 |
pmic | 0:211f27847e85 | 84 | // 3 = 119 6 = 952 |
pmic | 0:211f27847e85 | 85 | settings.gyro.sampleRate = 5; |
pmic | 0:211f27847e85 | 86 | // gyro cutoff frequency: value between 0-3 |
pmic | 0:211f27847e85 | 87 | // Actual value of cutoff frequency depends |
pmic | 0:211f27847e85 | 88 | // on sample rate. |
pmic | 0:211f27847e85 | 89 | // @476 Hz: 0 -> 21 Hz only if LPF2 is enabled, to do so you need to set xgWriteByte(CTRL_REG2_G, 0x02) to enable LPF 2, pmic 11.09.2019 |
pmic | 0:211f27847e85 | 90 | // 1 -> 28 Hz |
pmic | 0:211f27847e85 | 91 | // 2 -> 57 Hz |
pmic | 0:211f27847e85 | 92 | // 3 -> 100 Hz |
pmic | 0:211f27847e85 | 93 | settings.gyro.bandwidth = 1; |
pmic | 0:211f27847e85 | 94 | settings.gyro.lowPowerEnable = false; |
pmic | 0:211f27847e85 | 95 | settings.gyro.HPFEnable = false; |
pmic | 0:211f27847e85 | 96 | // Gyro HPF cutoff frequency: value between 0-9 |
pmic | 0:211f27847e85 | 97 | // Actual value depends on sample rate. Only applies |
pmic | 0:211f27847e85 | 98 | // if gyroHPFEnable is true. |
pmic | 0:211f27847e85 | 99 | settings.gyro.HPFCutoff = 0; |
pmic | 0:211f27847e85 | 100 | settings.gyro.flipX = false; |
pmic | 0:211f27847e85 | 101 | settings.gyro.flipY = false; |
pmic | 0:211f27847e85 | 102 | settings.gyro.flipZ = false; |
pmic | 0:211f27847e85 | 103 | settings.gyro.orientation = 0; |
pmic | 0:211f27847e85 | 104 | settings.gyro.latchInterrupt = true; |
pmic | 0:211f27847e85 | 105 | |
pmic | 0:211f27847e85 | 106 | settings.accel.enabled = true; |
pmic | 0:211f27847e85 | 107 | settings.accel.enableX = true; |
pmic | 0:211f27847e85 | 108 | settings.accel.enableY = true; |
pmic | 0:211f27847e85 | 109 | settings.accel.enableZ = true; |
pmic | 0:211f27847e85 | 110 | // accel scale can be 2, 4, 8, or 16 |
pmic | 0:211f27847e85 | 111 | settings.accel.scale = 2; |
pmic | 0:211f27847e85 | 112 | // accel sample rate can be 1-6 |
pmic | 0:211f27847e85 | 113 | // 1 = 10 Hz 4 = 238 Hz |
pmic | 0:211f27847e85 | 114 | // 2 = 50 Hz 5 = 476 Hz |
pmic | 0:211f27847e85 | 115 | // 3 = 119 Hz 6 = 952 Hz |
pmic | 0:211f27847e85 | 116 | settings.accel.sampleRate = 5; |
pmic | 0:211f27847e85 | 117 | // Accel cutoff freqeuncy can be any value between -1 - 3. |
pmic | 0:211f27847e85 | 118 | // -1 = bandwidth determined by sample rate |
pmic | 0:211f27847e85 | 119 | // 0 = 408 Hz 2 = 105 Hz |
pmic | 0:211f27847e85 | 120 | // 1 = 211 Hz 3 = 50 Hz |
pmic | 0:211f27847e85 | 121 | settings.accel.bandwidth = 3; |
pmic | 0:211f27847e85 | 122 | settings.accel.highResEnable = false; |
pmic | 0:211f27847e85 | 123 | // accelHighResBandwidth can be any value between 0-3 |
pmic | 0:211f27847e85 | 124 | // LP cutoff is set to a factor of sample rate |
pmic | 0:211f27847e85 | 125 | // 0 = ODR/50 2 = ODR/9 |
pmic | 0:211f27847e85 | 126 | // 1 = ODR/100 3 = ODR/400 |
pmic | 0:211f27847e85 | 127 | settings.accel.highResBandwidth = 0; |
pmic | 0:211f27847e85 | 128 | |
pmic | 0:211f27847e85 | 129 | settings.mag.enabled = true; |
pmic | 0:211f27847e85 | 130 | // mag scale can be 4, 8, 12, or 16 |
pmic | 0:211f27847e85 | 131 | settings.mag.scale = 4; |
pmic | 0:211f27847e85 | 132 | // mag data rate can be 0-7 |
pmic | 0:211f27847e85 | 133 | // 0 = 0.625 Hz 4 = 10 Hz |
pmic | 0:211f27847e85 | 134 | // 1 = 1.25 Hz 5 = 20 Hz |
pmic | 0:211f27847e85 | 135 | // 2 = 2.5 Hz 6 = 40 Hz |
pmic | 0:211f27847e85 | 136 | // 3 = 5 Hz 7 = 80 Hz |
pmic | 0:211f27847e85 | 137 | settings.mag.sampleRate = 7; |
pmic | 0:211f27847e85 | 138 | settings.mag.tempCompensationEnable = true; |
pmic | 0:211f27847e85 | 139 | // magPerformance can be any value between 0-3 |
pmic | 0:211f27847e85 | 140 | // 0 = Low power mode 2 = high performance |
pmic | 0:211f27847e85 | 141 | // 1 = medium performance 3 = ultra-high performance |
pmic | 0:211f27847e85 | 142 | settings.mag.XYPerformance = 2; |
pmic | 0:211f27847e85 | 143 | settings.mag.ZPerformance = 2; |
pmic | 0:211f27847e85 | 144 | settings.mag.lowPowerEnable = false; |
pmic | 0:211f27847e85 | 145 | // magOperatingMode can be 0-2 |
pmic | 0:211f27847e85 | 146 | // 0 = continuous conversion |
pmic | 0:211f27847e85 | 147 | // 1 = single-conversion |
pmic | 0:211f27847e85 | 148 | // 2 = power down |
pmic | 0:211f27847e85 | 149 | settings.mag.operatingMode = 0; |
pmic | 0:211f27847e85 | 150 | |
pmic | 0:211f27847e85 | 151 | settings.temp.enabled = true; |
pmic | 0:211f27847e85 | 152 | for (int i=0; i<3; i++) |
pmic | 0:211f27847e85 | 153 | { |
pmic | 0:211f27847e85 | 154 | gBias[i] = 0; |
pmic | 0:211f27847e85 | 155 | aBias[i] = 0; |
pmic | 0:211f27847e85 | 156 | mBias[i] = 0; |
pmic | 0:211f27847e85 | 157 | gBiasRaw[i] = 0; |
pmic | 0:211f27847e85 | 158 | aBiasRaw[i] = 0; |
pmic | 0:211f27847e85 | 159 | mBiasRaw[i] = 0; |
pmic | 0:211f27847e85 | 160 | } |
pmic | 0:211f27847e85 | 161 | _autoCalc = false; |
pmic | 0:211f27847e85 | 162 | } |
pmic | 0:211f27847e85 | 163 | |
pmic | 0:211f27847e85 | 164 | |
pmic | 0:211f27847e85 | 165 | uint16_t LSM9DS1::begin() |
pmic | 0:211f27847e85 | 166 | { |
pmic | 0:211f27847e85 | 167 | //! Todo: don't use _xgAddress or _mAddress, duplicating memory |
pmic | 0:211f27847e85 | 168 | _xgAddress = settings.device.agAddress; |
pmic | 0:211f27847e85 | 169 | _mAddress = settings.device.mAddress; |
pmic | 0:211f27847e85 | 170 | |
pmic | 0:211f27847e85 | 171 | constrainScales(); |
pmic | 0:211f27847e85 | 172 | // Once we have the scale values, we can calculate the resolution |
pmic | 0:211f27847e85 | 173 | // of each sensor. That's what these functions are for. One for each sensor |
pmic | 0:211f27847e85 | 174 | calcgRes(); // Calculate DPS / ADC tick, stored in gRes variable |
pmic | 0:211f27847e85 | 175 | calcmRes(); // Calculate Gs / ADC tick, stored in mRes variable |
pmic | 0:211f27847e85 | 176 | calcaRes(); // Calculate g / ADC tick, stored in aRes variable |
pmic | 0:211f27847e85 | 177 | |
pmic | 0:211f27847e85 | 178 | // Now, initialize our hardware interface. |
pmic | 0:211f27847e85 | 179 | if (settings.device.commInterface == IMU_MODE_I2C) // If we're using I2C |
pmic | 0:211f27847e85 | 180 | initI2C(); // Initialize I2C |
pmic | 0:211f27847e85 | 181 | else if (settings.device.commInterface == IMU_MODE_SPI) // else, if we're using SPI |
pmic | 0:211f27847e85 | 182 | initSPI(); // Initialize SPI |
pmic | 0:211f27847e85 | 183 | |
pmic | 0:211f27847e85 | 184 | // To verify communication, we can read from the WHO_AM_I register of |
pmic | 0:211f27847e85 | 185 | // each device. Store those in a variable so we can return them. |
pmic | 0:211f27847e85 | 186 | uint8_t mTest = mReadByte(WHO_AM_I_M); // Read the gyro WHO_AM_I |
pmic | 0:211f27847e85 | 187 | uint8_t xgTest = xgReadByte(WHO_AM_I_XG); // Read the accel/mag WHO_AM_I |
pmic | 0:211f27847e85 | 188 | printf("%x, %x, %x, %x\n\r", mTest, xgTest, _xgAddress, _mAddress); |
pmic | 0:211f27847e85 | 189 | uint16_t whoAmICombined = (xgTest << 8) | mTest; |
pmic | 0:211f27847e85 | 190 | |
pmic | 0:211f27847e85 | 191 | if (whoAmICombined != ((WHO_AM_I_AG_RSP << 8) | WHO_AM_I_M_RSP)) |
pmic | 0:211f27847e85 | 192 | return 0; |
pmic | 0:211f27847e85 | 193 | |
pmic | 0:211f27847e85 | 194 | // Gyro initialization stuff: |
pmic | 0:211f27847e85 | 195 | initGyro(); // This will "turn on" the gyro. Setting up interrupts, etc. |
pmic | 0:211f27847e85 | 196 | |
pmic | 0:211f27847e85 | 197 | // Accelerometer initialization stuff: |
pmic | 0:211f27847e85 | 198 | initAccel(); // "Turn on" all axes of the accel. Set up interrupts, etc. |
pmic | 0:211f27847e85 | 199 | |
pmic | 0:211f27847e85 | 200 | // Magnetometer initialization stuff: |
pmic | 0:211f27847e85 | 201 | initMag(); // "Turn on" all axes of the mag. Set up interrupts, etc. |
pmic | 0:211f27847e85 | 202 | |
pmic | 0:211f27847e85 | 203 | // Once everything is initialized, return the WHO_AM_I registers we read: |
pmic | 0:211f27847e85 | 204 | return whoAmICombined; |
pmic | 0:211f27847e85 | 205 | } |
pmic | 0:211f27847e85 | 206 | |
pmic | 0:211f27847e85 | 207 | float LSM9DS1::readGyroX(){return gyroX;} |
pmic | 0:211f27847e85 | 208 | float LSM9DS1::readGyroY(){return gyroY;} |
pmic | 0:211f27847e85 | 209 | float LSM9DS1::readGyroZ(){return gyroZ;} |
pmic | 0:211f27847e85 | 210 | float LSM9DS1::readAccX(){return accX;} |
pmic | 0:211f27847e85 | 211 | float LSM9DS1::readAccY(){return accY;} |
pmic | 0:211f27847e85 | 212 | float LSM9DS1::readAccZ(){return accZ;} |
pmic | 0:211f27847e85 | 213 | float LSM9DS1::readMagX(){return magX;} |
pmic | 0:211f27847e85 | 214 | float LSM9DS1::readMagY(){return magY;} |
pmic | 0:211f27847e85 | 215 | float LSM9DS1::readMagZ(){return magZ;} |
pmic | 0:211f27847e85 | 216 | |
pmic | 0:211f27847e85 | 217 | void LSM9DS1::initGyro() |
pmic | 0:211f27847e85 | 218 | { |
pmic | 0:211f27847e85 | 219 | uint8_t tempRegValue = 0; |
pmic | 0:211f27847e85 | 220 | |
pmic | 0:211f27847e85 | 221 | // CTRL_REG1_G (Default value: 0x00) |
pmic | 0:211f27847e85 | 222 | // [ODR_G2][ODR_G1][ODR_G0][FS_G1][FS_G0][0][BW_G1][BW_G0] |
pmic | 0:211f27847e85 | 223 | // ODR_G[2:0] - Output data rate selection |
pmic | 0:211f27847e85 | 224 | // FS_G[1:0] - Gyroscope full-scale selection |
pmic | 0:211f27847e85 | 225 | // BW_G[1:0] - Gyroscope bandwidth selection |
pmic | 0:211f27847e85 | 226 | |
pmic | 0:211f27847e85 | 227 | // To disable gyro, set sample rate bits to 0. We'll only set sample |
pmic | 0:211f27847e85 | 228 | // rate if the gyro is enabled. |
pmic | 0:211f27847e85 | 229 | if (settings.gyro.enabled) |
pmic | 0:211f27847e85 | 230 | { |
pmic | 0:211f27847e85 | 231 | tempRegValue = (settings.gyro.sampleRate & 0x07) << 5; |
pmic | 0:211f27847e85 | 232 | } |
pmic | 0:211f27847e85 | 233 | switch (settings.gyro.scale) |
pmic | 0:211f27847e85 | 234 | { |
pmic | 0:211f27847e85 | 235 | case 500: |
pmic | 0:211f27847e85 | 236 | tempRegValue |= (0x1 << 3); |
pmic | 0:211f27847e85 | 237 | break; |
pmic | 0:211f27847e85 | 238 | case 2000: |
pmic | 0:211f27847e85 | 239 | tempRegValue |= (0x3 << 3); |
pmic | 0:211f27847e85 | 240 | break; |
pmic | 0:211f27847e85 | 241 | // Otherwise we'll set it to 245 dps (0x0 << 4) |
pmic | 0:211f27847e85 | 242 | } |
pmic | 0:211f27847e85 | 243 | tempRegValue |= (settings.gyro.bandwidth & 0x3); |
pmic | 0:211f27847e85 | 244 | xgWriteByte(CTRL_REG1_G, tempRegValue); |
pmic | 0:211f27847e85 | 245 | |
pmic | 0:211f27847e85 | 246 | // CTRL_REG2_G (Default value: 0x00) |
pmic | 0:211f27847e85 | 247 | // [0][0][0][0][INT_SEL1][INT_SEL0][OUT_SEL1][OUT_SEL0] |
pmic | 0:211f27847e85 | 248 | // INT_SEL[1:0] - INT selection configuration |
pmic | 0:211f27847e85 | 249 | // OUT_SEL[1:0] - Out selection configuration |
pmic | 0:211f27847e85 | 250 | xgWriteByte(CTRL_REG2_G, 0x02); // use xgWriteByte(CTRL_REG2_G, 0x00); to disable LPF 2, pmic 11.09.2019 |
pmic | 0:211f27847e85 | 251 | |
pmic | 0:211f27847e85 | 252 | // CTRL_REG3_G (Default value: 0x00) |
pmic | 0:211f27847e85 | 253 | // [LP_mode][HP_EN][0][0][HPCF3_G][HPCF2_G][HPCF1_G][HPCF0_G] |
pmic | 0:211f27847e85 | 254 | // LP_mode - Low-power mode enable (0: disabled, 1: enabled) |
pmic | 0:211f27847e85 | 255 | // HP_EN - HPF enable (0:disabled, 1: enabled) |
pmic | 0:211f27847e85 | 256 | // HPCF_G[3:0] - HPF cutoff frequency |
pmic | 0:211f27847e85 | 257 | tempRegValue = settings.gyro.lowPowerEnable ? (1<<7) : 0; |
pmic | 0:211f27847e85 | 258 | if (settings.gyro.HPFEnable) |
pmic | 0:211f27847e85 | 259 | { |
pmic | 0:211f27847e85 | 260 | tempRegValue |= (1<<6) | (settings.gyro.HPFCutoff & 0x0F); |
pmic | 0:211f27847e85 | 261 | } |
pmic | 0:211f27847e85 | 262 | xgWriteByte(CTRL_REG3_G, tempRegValue); |
pmic | 0:211f27847e85 | 263 | |
pmic | 0:211f27847e85 | 264 | // CTRL_REG4 (Default value: 0x38) |
pmic | 0:211f27847e85 | 265 | // [0][0][Zen_G][Yen_G][Xen_G][0][LIR_XL1][4D_XL1] |
pmic | 0:211f27847e85 | 266 | // Zen_G - Z-axis output enable (0:disable, 1:enable) |
pmic | 0:211f27847e85 | 267 | // Yen_G - Y-axis output enable (0:disable, 1:enable) |
pmic | 0:211f27847e85 | 268 | // Xen_G - X-axis output enable (0:disable, 1:enable) |
pmic | 0:211f27847e85 | 269 | // LIR_XL1 - Latched interrupt (0:not latched, 1:latched) |
pmic | 0:211f27847e85 | 270 | // 4D_XL1 - 4D option on interrupt (0:6D used, 1:4D used) |
pmic | 0:211f27847e85 | 271 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 272 | if (settings.gyro.enableZ) tempRegValue |= (1<<5); |
pmic | 0:211f27847e85 | 273 | if (settings.gyro.enableY) tempRegValue |= (1<<4); |
pmic | 0:211f27847e85 | 274 | if (settings.gyro.enableX) tempRegValue |= (1<<3); |
pmic | 0:211f27847e85 | 275 | if (settings.gyro.latchInterrupt) tempRegValue |= (1<<1); |
pmic | 0:211f27847e85 | 276 | xgWriteByte(CTRL_REG4, tempRegValue); |
pmic | 0:211f27847e85 | 277 | |
pmic | 0:211f27847e85 | 278 | // ORIENT_CFG_G (Default value: 0x00) |
pmic | 0:211f27847e85 | 279 | // [0][0][SignX_G][SignY_G][SignZ_G][Orient_2][Orient_1][Orient_0] |
pmic | 0:211f27847e85 | 280 | // SignX_G - Pitch axis (X) angular rate sign (0: positive, 1: negative) |
pmic | 0:211f27847e85 | 281 | // Orient [2:0] - Directional user orientation selection |
pmic | 0:211f27847e85 | 282 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 283 | if (settings.gyro.flipX) tempRegValue |= (1<<5); |
pmic | 0:211f27847e85 | 284 | if (settings.gyro.flipY) tempRegValue |= (1<<4); |
pmic | 0:211f27847e85 | 285 | if (settings.gyro.flipZ) tempRegValue |= (1<<3); |
pmic | 0:211f27847e85 | 286 | xgWriteByte(ORIENT_CFG_G, tempRegValue); |
pmic | 0:211f27847e85 | 287 | } |
pmic | 0:211f27847e85 | 288 | |
pmic | 0:211f27847e85 | 289 | void LSM9DS1::initAccel() |
pmic | 0:211f27847e85 | 290 | { |
pmic | 0:211f27847e85 | 291 | uint8_t tempRegValue = 0; |
pmic | 0:211f27847e85 | 292 | |
pmic | 0:211f27847e85 | 293 | // CTRL_REG5_XL (0x1F) (Default value: 0x38) |
pmic | 0:211f27847e85 | 294 | // [DEC_1][DEC_0][Zen_XL][Yen_XL][Zen_XL][0][0][0] |
pmic | 0:211f27847e85 | 295 | // DEC[0:1] - Decimation of accel data on OUT REG and FIFO. |
pmic | 0:211f27847e85 | 296 | // 00: None, 01: 2 samples, 10: 4 samples 11: 8 samples |
pmic | 0:211f27847e85 | 297 | // Zen_XL - Z-axis output enabled |
pmic | 0:211f27847e85 | 298 | // Yen_XL - Y-axis output enabled |
pmic | 0:211f27847e85 | 299 | // Xen_XL - X-axis output enabled |
pmic | 0:211f27847e85 | 300 | if (settings.accel.enableZ) tempRegValue |= (1<<5); |
pmic | 0:211f27847e85 | 301 | if (settings.accel.enableY) tempRegValue |= (1<<4); |
pmic | 0:211f27847e85 | 302 | if (settings.accel.enableX) tempRegValue |= (1<<3); |
pmic | 0:211f27847e85 | 303 | |
pmic | 0:211f27847e85 | 304 | xgWriteByte(CTRL_REG5_XL, tempRegValue); |
pmic | 0:211f27847e85 | 305 | |
pmic | 0:211f27847e85 | 306 | // CTRL_REG6_XL (0x20) (Default value: 0x00) |
pmic | 0:211f27847e85 | 307 | // [ODR_XL2][ODR_XL1][ODR_XL0][FS1_XL][FS0_XL][BW_SCAL_ODR][BW_XL1][BW_XL0] |
pmic | 0:211f27847e85 | 308 | // ODR_XL[2:0] - Output data rate & power mode selection |
pmic | 0:211f27847e85 | 309 | // FS_XL[1:0] - Full-scale selection |
pmic | 0:211f27847e85 | 310 | // BW_SCAL_ODR - Bandwidth selection |
pmic | 0:211f27847e85 | 311 | // BW_XL[1:0] - Anti-aliasing filter bandwidth selection |
pmic | 0:211f27847e85 | 312 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 313 | // To disable the accel, set the sampleRate bits to 0. |
pmic | 0:211f27847e85 | 314 | if (settings.accel.enabled) |
pmic | 0:211f27847e85 | 315 | { |
pmic | 0:211f27847e85 | 316 | tempRegValue |= (settings.accel.sampleRate & 0x07) << 5; |
pmic | 0:211f27847e85 | 317 | } |
pmic | 0:211f27847e85 | 318 | switch (settings.accel.scale) |
pmic | 0:211f27847e85 | 319 | { |
pmic | 0:211f27847e85 | 320 | case 4: |
pmic | 0:211f27847e85 | 321 | tempRegValue |= (0x2 << 3); |
pmic | 0:211f27847e85 | 322 | break; |
pmic | 0:211f27847e85 | 323 | case 8: |
pmic | 0:211f27847e85 | 324 | tempRegValue |= (0x3 << 3); |
pmic | 0:211f27847e85 | 325 | break; |
pmic | 0:211f27847e85 | 326 | case 16: |
pmic | 0:211f27847e85 | 327 | tempRegValue |= (0x1 << 3); |
pmic | 0:211f27847e85 | 328 | break; |
pmic | 0:211f27847e85 | 329 | // Otherwise it'll be set to 2g (0x0 << 3) |
pmic | 0:211f27847e85 | 330 | } |
pmic | 0:211f27847e85 | 331 | if (settings.accel.bandwidth >= 0) |
pmic | 0:211f27847e85 | 332 | { |
pmic | 0:211f27847e85 | 333 | tempRegValue |= (1<<2); // Set BW_SCAL_ODR |
pmic | 0:211f27847e85 | 334 | tempRegValue |= (settings.accel.bandwidth & 0x03); |
pmic | 0:211f27847e85 | 335 | } |
pmic | 0:211f27847e85 | 336 | xgWriteByte(CTRL_REG6_XL, tempRegValue); |
pmic | 0:211f27847e85 | 337 | |
pmic | 0:211f27847e85 | 338 | // CTRL_REG7_XL (0x21) (Default value: 0x00) |
pmic | 0:211f27847e85 | 339 | // [HR][DCF1][DCF0][0][0][FDS][0][HPIS1] |
pmic | 0:211f27847e85 | 340 | // HR - High resolution mode (0: disable, 1: enable) |
pmic | 0:211f27847e85 | 341 | // DCF[1:0] - Digital filter cutoff frequency |
pmic | 0:211f27847e85 | 342 | // FDS - Filtered data selection |
pmic | 0:211f27847e85 | 343 | // HPIS1 - HPF enabled for interrupt function |
pmic | 0:211f27847e85 | 344 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 345 | if (settings.accel.highResEnable) |
pmic | 0:211f27847e85 | 346 | { |
pmic | 0:211f27847e85 | 347 | tempRegValue |= (1<<7); // Set HR bit |
pmic | 0:211f27847e85 | 348 | tempRegValue |= (settings.accel.highResBandwidth & 0x3) << 5; |
pmic | 0:211f27847e85 | 349 | } |
pmic | 0:211f27847e85 | 350 | xgWriteByte(CTRL_REG7_XL, tempRegValue); |
pmic | 0:211f27847e85 | 351 | } |
pmic | 0:211f27847e85 | 352 | |
pmic | 0:211f27847e85 | 353 | // This is a function that uses the FIFO to accumulate sample of accelerometer and gyro data, average |
pmic | 0:211f27847e85 | 354 | // them, scales them to gs and deg/s, respectively, and then passes the biases to the main sketch |
pmic | 0:211f27847e85 | 355 | // for subtraction from all subsequent data. There are no gyro and accelerometer bias registers to store |
pmic | 0:211f27847e85 | 356 | // the data as there are in the ADXL345, a precursor to the LSM9DS0, or the MPU-9150, so we have to |
pmic | 0:211f27847e85 | 357 | // subtract the biases ourselves. This results in a more accurate measurement in general and can |
pmic | 0:211f27847e85 | 358 | // remove errors due to imprecise or varying initial placement. Calibration of sensor data in this manner |
pmic | 0:211f27847e85 | 359 | // is good practice. |
pmic | 0:211f27847e85 | 360 | void LSM9DS1::calibrate(bool autoCalc) |
pmic | 0:211f27847e85 | 361 | { |
pmic | 0:211f27847e85 | 362 | uint8_t data[6] = {0, 0, 0, 0, 0, 0}; |
pmic | 0:211f27847e85 | 363 | uint8_t samples = 0; |
pmic | 0:211f27847e85 | 364 | int ii; |
pmic | 0:211f27847e85 | 365 | int32_t aBiasRawTemp[3] = {0, 0, 0}; |
pmic | 0:211f27847e85 | 366 | int32_t gBiasRawTemp[3] = {0, 0, 0}; |
pmic | 0:211f27847e85 | 367 | |
pmic | 0:211f27847e85 | 368 | // Turn on FIFO and set threshold to 32 samples |
pmic | 0:211f27847e85 | 369 | enableFIFO(true); |
pmic | 0:211f27847e85 | 370 | setFIFO(FIFO_THS, 0x1F); |
pmic | 0:211f27847e85 | 371 | while (samples < 0x7F) |
pmic | 0:211f27847e85 | 372 | { |
pmic | 0:211f27847e85 | 373 | samples = (xgReadByte(FIFO_SRC) & 0x3F); // Read number of stored samples |
pmic | 0:211f27847e85 | 374 | } |
pmic | 0:211f27847e85 | 375 | for(ii = 0; ii < samples ; ii++) |
pmic | 0:211f27847e85 | 376 | { // Read the gyro data stored in the FIFO |
pmic | 0:211f27847e85 | 377 | updateGyro(); |
pmic | 0:211f27847e85 | 378 | gBiasRawTemp[0] += gx; |
pmic | 0:211f27847e85 | 379 | gBiasRawTemp[1] += gy; |
pmic | 0:211f27847e85 | 380 | gBiasRawTemp[2] += gz; |
pmic | 0:211f27847e85 | 381 | updateAcc(); |
pmic | 0:211f27847e85 | 382 | aBiasRawTemp[0] += ax; |
pmic | 0:211f27847e85 | 383 | aBiasRawTemp[1] += ay; |
pmic | 0:211f27847e85 | 384 | aBiasRawTemp[2] += az - (int32_t)(1.0f/aRes); // Assumes sensor facing up! |
pmic | 0:211f27847e85 | 385 | } |
pmic | 0:211f27847e85 | 386 | for (ii = 0; ii < 3; ii++) |
pmic | 0:211f27847e85 | 387 | { |
pmic | 0:211f27847e85 | 388 | gBiasRaw[ii] = gBiasRawTemp[ii] / samples; |
pmic | 0:211f27847e85 | 389 | gBias[ii] = calcGyro(gBiasRaw[ii]); |
pmic | 0:211f27847e85 | 390 | aBiasRaw[ii] = aBiasRawTemp[ii] / samples; |
pmic | 0:211f27847e85 | 391 | aBias[ii] = calcAccel(aBiasRaw[ii]); |
pmic | 0:211f27847e85 | 392 | } |
pmic | 0:211f27847e85 | 393 | |
pmic | 0:211f27847e85 | 394 | enableFIFO(false); |
pmic | 0:211f27847e85 | 395 | setFIFO(FIFO_OFF, 0x00); |
pmic | 0:211f27847e85 | 396 | |
pmic | 0:211f27847e85 | 397 | if (autoCalc) _autoCalc = true; |
pmic | 0:211f27847e85 | 398 | } |
pmic | 0:211f27847e85 | 399 | |
pmic | 0:211f27847e85 | 400 | void LSM9DS1::calibrateMag(bool loadIn) |
pmic | 0:211f27847e85 | 401 | { |
pmic | 0:211f27847e85 | 402 | int i, j; |
pmic | 0:211f27847e85 | 403 | int16_t magMin[3] = {0, 0, 0}; |
pmic | 0:211f27847e85 | 404 | int16_t magMax[3] = {0, 0, 0}; // The road warrior |
pmic | 0:211f27847e85 | 405 | |
pmic | 0:211f27847e85 | 406 | for (i=0; i<128; i++) |
pmic | 0:211f27847e85 | 407 | { |
pmic | 0:211f27847e85 | 408 | while (!magAvailable()); |
pmic | 0:211f27847e85 | 409 | updateMag(); |
pmic | 0:211f27847e85 | 410 | int16_t magTemp[3] = {0, 0, 0}; |
pmic | 0:211f27847e85 | 411 | magTemp[0] = mx; |
pmic | 0:211f27847e85 | 412 | magTemp[1] = my; |
pmic | 0:211f27847e85 | 413 | magTemp[2] = mz; |
pmic | 0:211f27847e85 | 414 | for (j = 0; j < 3; j++) |
pmic | 0:211f27847e85 | 415 | { |
pmic | 0:211f27847e85 | 416 | if (magTemp[j] > magMax[j]) magMax[j] = magTemp[j]; |
pmic | 0:211f27847e85 | 417 | if (magTemp[j] < magMin[j]) magMin[j] = magTemp[j]; |
pmic | 0:211f27847e85 | 418 | } |
pmic | 0:211f27847e85 | 419 | } |
pmic | 0:211f27847e85 | 420 | for (j = 0; j < 3; j++) |
pmic | 0:211f27847e85 | 421 | { |
pmic | 0:211f27847e85 | 422 | mBiasRaw[j] = (magMax[j] + magMin[j]) / 2; |
pmic | 0:211f27847e85 | 423 | mBias[j] = calcMag(mBiasRaw[j]); |
pmic | 0:211f27847e85 | 424 | if (loadIn) |
pmic | 0:211f27847e85 | 425 | magOffset(j, mBiasRaw[j]); |
pmic | 0:211f27847e85 | 426 | } |
pmic | 0:211f27847e85 | 427 | |
pmic | 0:211f27847e85 | 428 | } |
pmic | 0:211f27847e85 | 429 | void LSM9DS1::magOffset(uint8_t axis, int16_t offset) |
pmic | 0:211f27847e85 | 430 | { |
pmic | 0:211f27847e85 | 431 | if (axis > 2) |
pmic | 0:211f27847e85 | 432 | return; |
pmic | 0:211f27847e85 | 433 | uint8_t msb, lsb; |
pmic | 0:211f27847e85 | 434 | msb = (offset & 0xFF00) >> 8; |
pmic | 0:211f27847e85 | 435 | lsb = offset & 0x00FF; |
pmic | 0:211f27847e85 | 436 | mWriteByte(OFFSET_X_REG_L_M + (2 * axis), lsb); |
pmic | 0:211f27847e85 | 437 | mWriteByte(OFFSET_X_REG_H_M + (2 * axis), msb); |
pmic | 0:211f27847e85 | 438 | } |
pmic | 0:211f27847e85 | 439 | |
pmic | 0:211f27847e85 | 440 | void LSM9DS1::initMag() |
pmic | 0:211f27847e85 | 441 | { |
pmic | 0:211f27847e85 | 442 | uint8_t tempRegValue = 0; |
pmic | 0:211f27847e85 | 443 | |
pmic | 0:211f27847e85 | 444 | // CTRL_REG1_M (Default value: 0x10) |
pmic | 0:211f27847e85 | 445 | // [TEMP_COMP][OM1][OM0][DO2][DO1][DO0][0][ST] |
pmic | 0:211f27847e85 | 446 | // TEMP_COMP - Temperature compensation |
pmic | 0:211f27847e85 | 447 | // OM[1:0] - X & Y axes op mode selection |
pmic | 0:211f27847e85 | 448 | // 00:low-power, 01:medium performance |
pmic | 0:211f27847e85 | 449 | // 10: high performance, 11:ultra-high performance |
pmic | 0:211f27847e85 | 450 | // DO[2:0] - Output data rate selection |
pmic | 0:211f27847e85 | 451 | // ST - Self-test enable |
pmic | 0:211f27847e85 | 452 | if (settings.mag.tempCompensationEnable) tempRegValue |= (1<<7); |
pmic | 0:211f27847e85 | 453 | tempRegValue |= (settings.mag.XYPerformance & 0x3) << 5; |
pmic | 0:211f27847e85 | 454 | tempRegValue |= (settings.mag.sampleRate & 0x7) << 2; |
pmic | 0:211f27847e85 | 455 | // mWriteByte(CTRL_REG1_M, tempRegValue); |
pmic | 0:211f27847e85 | 456 | // pmic 21.09.2019, settings now static |
pmic | 0:211f27847e85 | 457 | // use 0xC2 for temperature compensation on, Fast ODR -> 300 Hz undocumented mode high performance |
pmic | 0:211f27847e85 | 458 | // use 0x42 for temperature compensation off, Fast ODR -> 300 Hz undocumented mode high performance |
pmic | 0:211f27847e85 | 459 | // use 0xE2 for temperature compensation on, Fast ODR -> 155 Hz undocumented mode ultra high performance |
pmic | 0:211f27847e85 | 460 | // use 0x62 for temperature compensation off, Fast ODR -> 155 Hz undocumented mode ultra high performance |
pmic | 0:211f27847e85 | 461 | // use 0xA2 for temperature compensation on, Fast ODR -> 155 Hz undocumented mode medium performance |
pmic | 0:211f27847e85 | 462 | // use 0x22 for temperature compensation off, Fast ODR -> 155 Hz undocumented mode medium performance |
pmic | 0:211f27847e85 | 463 | mWriteByte(CTRL_REG1_M, 0xC2); |
pmic | 0:211f27847e85 | 464 | |
pmic | 0:211f27847e85 | 465 | // CTRL_REG2_M (Default value 0x00) |
pmic | 0:211f27847e85 | 466 | // [0][FS1][FS0][0][REBOOT][SOFT_RST][0][0] |
pmic | 0:211f27847e85 | 467 | // FS[1:0] - Full-scale configuration |
pmic | 0:211f27847e85 | 468 | // REBOOT - Reboot memory content (0:normal, 1:reboot) |
pmic | 0:211f27847e85 | 469 | // SOFT_RST - Reset config and user registers (0:default, 1:reset) |
pmic | 0:211f27847e85 | 470 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 471 | switch (settings.mag.scale) |
pmic | 0:211f27847e85 | 472 | { |
pmic | 0:211f27847e85 | 473 | case 8: |
pmic | 0:211f27847e85 | 474 | tempRegValue |= (0x1 << 5); |
pmic | 0:211f27847e85 | 475 | break; |
pmic | 0:211f27847e85 | 476 | case 12: |
pmic | 0:211f27847e85 | 477 | tempRegValue |= (0x2 << 5); |
pmic | 0:211f27847e85 | 478 | break; |
pmic | 0:211f27847e85 | 479 | case 16: |
pmic | 0:211f27847e85 | 480 | tempRegValue |= (0x3 << 5); |
pmic | 0:211f27847e85 | 481 | break; |
pmic | 0:211f27847e85 | 482 | // Otherwise we'll default to 4 gauss (00) |
pmic | 0:211f27847e85 | 483 | } |
pmic | 0:211f27847e85 | 484 | mWriteByte(CTRL_REG2_M, tempRegValue); // +/-4Gauss |
pmic | 0:211f27847e85 | 485 | |
pmic | 0:211f27847e85 | 486 | // CTRL_REG3_M (Default value: 0x03) |
pmic | 0:211f27847e85 | 487 | // [I2C_DISABLE][0][LP][0][0][SIM][MD1][MD0] |
pmic | 0:211f27847e85 | 488 | // I2C_DISABLE - Disable I2C interace (0:enable, 1:disable) |
pmic | 0:211f27847e85 | 489 | // LP - Low-power mode cofiguration (1:enable) |
pmic | 0:211f27847e85 | 490 | // SIM - SPI mode selection (0:write-only, 1:read/write enable) |
pmic | 0:211f27847e85 | 491 | // MD[1:0] - Operating mode |
pmic | 0:211f27847e85 | 492 | // 00:continuous conversion, 01:single-conversion, |
pmic | 0:211f27847e85 | 493 | // 10,11: Power-down |
pmic | 0:211f27847e85 | 494 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 495 | if (settings.mag.lowPowerEnable) tempRegValue |= (1<<5); |
pmic | 0:211f27847e85 | 496 | tempRegValue |= (settings.mag.operatingMode & 0x3); |
pmic | 0:211f27847e85 | 497 | mWriteByte(CTRL_REG3_M, tempRegValue); // Continuous conversion mode |
pmic | 0:211f27847e85 | 498 | |
pmic | 0:211f27847e85 | 499 | // CTRL_REG4_M (Default value: 0x00) |
pmic | 0:211f27847e85 | 500 | // [0][0][0][0][OMZ1][OMZ0][BLE][0] |
pmic | 0:211f27847e85 | 501 | // OMZ[1:0] - Z-axis operative mode selection |
pmic | 0:211f27847e85 | 502 | // 00:low-power mode, 01:medium performance |
pmic | 0:211f27847e85 | 503 | // 10:high performance, 11:ultra-high performance |
pmic | 0:211f27847e85 | 504 | // BLE - Big/little endian data |
pmic | 0:211f27847e85 | 505 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 506 | tempRegValue = (settings.mag.ZPerformance & 0x3) << 2; |
pmic | 0:211f27847e85 | 507 | mWriteByte(CTRL_REG4_M, tempRegValue); |
pmic | 0:211f27847e85 | 508 | |
pmic | 0:211f27847e85 | 509 | // CTRL_REG5_M (Default value: 0x00) |
pmic | 0:211f27847e85 | 510 | // [0][BDU][0][0][0][0][0][0] |
pmic | 0:211f27847e85 | 511 | // BDU - Block data update for magnetic data |
pmic | 0:211f27847e85 | 512 | // 0:continuous, 1:not updated until MSB/LSB are read |
pmic | 0:211f27847e85 | 513 | tempRegValue = 0; |
pmic | 0:211f27847e85 | 514 | mWriteByte(CTRL_REG5_M, tempRegValue); |
pmic | 0:211f27847e85 | 515 | } |
pmic | 0:211f27847e85 | 516 | |
pmic | 0:211f27847e85 | 517 | uint8_t LSM9DS1::accelAvailable() |
pmic | 0:211f27847e85 | 518 | { |
pmic | 0:211f27847e85 | 519 | uint8_t status = xgReadByte(STATUS_REG_1); |
pmic | 0:211f27847e85 | 520 | |
pmic | 0:211f27847e85 | 521 | return (status & (1<<0)); |
pmic | 0:211f27847e85 | 522 | } |
pmic | 0:211f27847e85 | 523 | |
pmic | 0:211f27847e85 | 524 | uint8_t LSM9DS1::gyroAvailable() |
pmic | 0:211f27847e85 | 525 | { |
pmic | 0:211f27847e85 | 526 | uint8_t status = xgReadByte(STATUS_REG_1); |
pmic | 0:211f27847e85 | 527 | |
pmic | 0:211f27847e85 | 528 | return ((status & (1<<1)) >> 1); |
pmic | 0:211f27847e85 | 529 | } |
pmic | 0:211f27847e85 | 530 | |
pmic | 0:211f27847e85 | 531 | uint8_t LSM9DS1::tempAvailable() |
pmic | 0:211f27847e85 | 532 | { |
pmic | 0:211f27847e85 | 533 | uint8_t status = xgReadByte(STATUS_REG_1); |
pmic | 0:211f27847e85 | 534 | |
pmic | 0:211f27847e85 | 535 | return ((status & (1<<2)) >> 2); |
pmic | 0:211f27847e85 | 536 | } |
pmic | 0:211f27847e85 | 537 | |
pmic | 0:211f27847e85 | 538 | uint8_t LSM9DS1::magAvailable(lsm9ds1_axis axis) |
pmic | 0:211f27847e85 | 539 | { |
pmic | 0:211f27847e85 | 540 | uint8_t status; |
pmic | 0:211f27847e85 | 541 | status = mReadByte(STATUS_REG_M); |
pmic | 0:211f27847e85 | 542 | |
pmic | 0:211f27847e85 | 543 | return ((status & (1<<axis)) >> axis); |
pmic | 0:211f27847e85 | 544 | } |
pmic | 0:211f27847e85 | 545 | |
pmic | 0:211f27847e85 | 546 | void LSM9DS1::updateAcc() |
pmic | 0:211f27847e85 | 547 | { |
pmic | 0:211f27847e85 | 548 | uint8_t temp[6]; // We'll read six bytes from the accelerometer into temp |
pmic | 0:211f27847e85 | 549 | xgReadBytes(OUT_X_L_XL, temp, 6); // Read 6 bytes, beginning at OUT_X_L_XL |
pmic | 0:211f27847e85 | 550 | ax = (temp[1] << 8) | temp[0]; // Store x-axis values into ax |
pmic | 0:211f27847e85 | 551 | ay = (temp[3] << 8) | temp[2]; // Store y-axis values into ay |
pmic | 0:211f27847e85 | 552 | az = (temp[5] << 8) | temp[4]; // Store z-axis values into az |
pmic | 0:211f27847e85 | 553 | if (_autoCalc) |
pmic | 0:211f27847e85 | 554 | { |
pmic | 0:211f27847e85 | 555 | ax -= aBiasRaw[X_AXIS]; |
pmic | 0:211f27847e85 | 556 | ay -= aBiasRaw[Y_AXIS]; |
pmic | 0:211f27847e85 | 557 | az -= aBiasRaw[Z_AXIS]; |
pmic | 0:211f27847e85 | 558 | } |
pmic | 0:211f27847e85 | 559 | accX = static_cast<float>(ax)/32768.0f*2.0f*9.81f; |
pmic | 0:211f27847e85 | 560 | accY = static_cast<float>(ay)/32768.0f*2.0f*9.81f; |
pmic | 0:211f27847e85 | 561 | accZ = static_cast<float>(az)/32768.0f*2.0f*9.81f; |
pmic | 0:211f27847e85 | 562 | } |
pmic | 0:211f27847e85 | 563 | |
pmic | 0:211f27847e85 | 564 | int16_t LSM9DS1::updateAcc(lsm9ds1_axis axis) |
pmic | 0:211f27847e85 | 565 | { |
pmic | 0:211f27847e85 | 566 | uint8_t temp[2]; |
pmic | 0:211f27847e85 | 567 | int16_t value; |
pmic | 0:211f27847e85 | 568 | xgReadBytes(OUT_X_L_XL + (2 * axis), temp, 2); |
pmic | 0:211f27847e85 | 569 | value = (temp[1] << 8) | temp[0]; |
pmic | 0:211f27847e85 | 570 | |
pmic | 0:211f27847e85 | 571 | if (_autoCalc) |
pmic | 0:211f27847e85 | 572 | value -= aBiasRaw[axis]; |
pmic | 0:211f27847e85 | 573 | |
pmic | 0:211f27847e85 | 574 | return value; |
pmic | 0:211f27847e85 | 575 | } |
pmic | 0:211f27847e85 | 576 | |
pmic | 0:211f27847e85 | 577 | void LSM9DS1::updateMag() |
pmic | 0:211f27847e85 | 578 | { |
pmic | 0:211f27847e85 | 579 | uint8_t temp[6]; // We'll read six bytes from the mag into temp |
pmic | 0:211f27847e85 | 580 | mReadBytes(OUT_X_L_M, temp, 6); // Read 6 bytes, beginning at OUT_X_L_M |
pmic | 0:211f27847e85 | 581 | mx = (temp[1] << 8) | temp[0]; // Store x-axis values into mx |
pmic | 0:211f27847e85 | 582 | my = (temp[3] << 8) | temp[2]; // Store y-axis values into my |
pmic | 0:211f27847e85 | 583 | mz = (temp[5] << 8) | temp[4]; // Store z-axis values into mz |
pmic | 0:211f27847e85 | 584 | |
pmic | 0:211f27847e85 | 585 | magX = static_cast<float>(mx)/32768.0f*4.0f; |
pmic | 0:211f27847e85 | 586 | magY = static_cast<float>(my)/32768.0f*4.0f; |
pmic | 0:211f27847e85 | 587 | magZ = static_cast<float>(mz)/32768.0f*4.0f; |
pmic | 0:211f27847e85 | 588 | } |
pmic | 0:211f27847e85 | 589 | |
pmic | 0:211f27847e85 | 590 | int16_t LSM9DS1::updateMag(lsm9ds1_axis axis) |
pmic | 0:211f27847e85 | 591 | { |
pmic | 0:211f27847e85 | 592 | uint8_t temp[2]; |
pmic | 0:211f27847e85 | 593 | mReadBytes(OUT_X_L_M + (2 * axis), temp, 2); |
pmic | 0:211f27847e85 | 594 | return (temp[1] << 8) | temp[0]; |
pmic | 0:211f27847e85 | 595 | } |
pmic | 0:211f27847e85 | 596 | |
pmic | 0:211f27847e85 | 597 | void LSM9DS1::readTemp() |
pmic | 0:211f27847e85 | 598 | { |
pmic | 0:211f27847e85 | 599 | uint8_t temp[2]; // We'll read two bytes from the temperature sensor into temp |
pmic | 0:211f27847e85 | 600 | xgReadBytes(OUT_TEMP_L, temp, 2); // Read 2 bytes, beginning at OUT_TEMP_L |
pmic | 0:211f27847e85 | 601 | temperature = ((int16_t)temp[1] << 8) | temp[0]; |
pmic | 0:211f27847e85 | 602 | } |
pmic | 0:211f27847e85 | 603 | |
pmic | 0:211f27847e85 | 604 | void LSM9DS1::updateGyro() |
pmic | 0:211f27847e85 | 605 | { |
pmic | 0:211f27847e85 | 606 | uint8_t temp[6]; // We'll read six bytes from the gyro into temp |
pmic | 0:211f27847e85 | 607 | xgReadBytes(OUT_X_L_G, temp, 6); // Read 6 bytes, beginning at OUT_X_L_G |
pmic | 0:211f27847e85 | 608 | gx = (temp[1] << 8) | temp[0]; // Store x-axis values into gx |
pmic | 0:211f27847e85 | 609 | gy = (temp[3] << 8) | temp[2]; // Store y-axis values into gy |
pmic | 0:211f27847e85 | 610 | gz = (temp[5] << 8) | temp[4]; // Store z-axis values into gz |
pmic | 0:211f27847e85 | 611 | if (_autoCalc) |
pmic | 0:211f27847e85 | 612 | { |
pmic | 0:211f27847e85 | 613 | gx -= gBiasRaw[X_AXIS]; |
pmic | 0:211f27847e85 | 614 | gy -= gBiasRaw[Y_AXIS]; |
pmic | 0:211f27847e85 | 615 | gz -= gBiasRaw[Z_AXIS]; |
pmic | 0:211f27847e85 | 616 | } |
pmic | 0:211f27847e85 | 617 | gyroX = static_cast<float>(gx)/32768.0f*(float)settings.gyro.scale*3.14159265358979323846f/180.0f * 1.17f; // measured correction 1.17, pmic 04.09.2019 |
pmic | 0:211f27847e85 | 618 | gyroY = static_cast<float>(gy)/32768.0f*(float)settings.gyro.scale*3.14159265358979323846f/180.0f * 1.17f; |
pmic | 0:211f27847e85 | 619 | gyroZ = static_cast<float>(gz)/32768.0f*(float)settings.gyro.scale*3.14159265358979323846f/180.0f * 1.17f; |
pmic | 0:211f27847e85 | 620 | } |
pmic | 0:211f27847e85 | 621 | |
pmic | 0:211f27847e85 | 622 | int16_t LSM9DS1::updateGyro(lsm9ds1_axis axis) |
pmic | 0:211f27847e85 | 623 | { |
pmic | 0:211f27847e85 | 624 | uint8_t temp[2]; |
pmic | 0:211f27847e85 | 625 | int16_t value; |
pmic | 0:211f27847e85 | 626 | |
pmic | 0:211f27847e85 | 627 | xgReadBytes(OUT_X_L_G + (2 * axis), temp, 2); |
pmic | 0:211f27847e85 | 628 | |
pmic | 0:211f27847e85 | 629 | value = (temp[1] << 8) | temp[0]; |
pmic | 0:211f27847e85 | 630 | |
pmic | 0:211f27847e85 | 631 | if (_autoCalc) |
pmic | 0:211f27847e85 | 632 | value -= gBiasRaw[axis]; |
pmic | 0:211f27847e85 | 633 | |
pmic | 0:211f27847e85 | 634 | return value; |
pmic | 0:211f27847e85 | 635 | } |
pmic | 0:211f27847e85 | 636 | |
pmic | 0:211f27847e85 | 637 | float LSM9DS1::calcGyro(int16_t gyro) |
pmic | 0:211f27847e85 | 638 | { |
pmic | 0:211f27847e85 | 639 | // Return the gyro raw reading times our pre-calculated DPS / (ADC tick): |
pmic | 0:211f27847e85 | 640 | return gRes * gyro; |
pmic | 0:211f27847e85 | 641 | } |
pmic | 0:211f27847e85 | 642 | |
pmic | 0:211f27847e85 | 643 | float LSM9DS1::calcAccel(int16_t accel) |
pmic | 0:211f27847e85 | 644 | { |
pmic | 0:211f27847e85 | 645 | // Return the accel raw reading times our pre-calculated g's / (ADC tick): |
pmic | 0:211f27847e85 | 646 | return aRes * accel; |
pmic | 0:211f27847e85 | 647 | } |
pmic | 0:211f27847e85 | 648 | |
pmic | 0:211f27847e85 | 649 | float LSM9DS1::calcMag(int16_t mag) |
pmic | 0:211f27847e85 | 650 | { |
pmic | 0:211f27847e85 | 651 | // Return the mag raw reading times our pre-calculated Gs / (ADC tick): |
pmic | 0:211f27847e85 | 652 | return mRes * mag; |
pmic | 0:211f27847e85 | 653 | } |
pmic | 0:211f27847e85 | 654 | |
pmic | 0:211f27847e85 | 655 | void LSM9DS1::setGyroScale(uint16_t gScl) |
pmic | 0:211f27847e85 | 656 | { |
pmic | 0:211f27847e85 | 657 | // Read current value of CTRL_REG1_G: |
pmic | 0:211f27847e85 | 658 | uint8_t ctrl1RegValue = xgReadByte(CTRL_REG1_G); |
pmic | 0:211f27847e85 | 659 | // Mask out scale bits (3 & 4): |
pmic | 0:211f27847e85 | 660 | ctrl1RegValue &= 0xE7; |
pmic | 0:211f27847e85 | 661 | switch (gScl) |
pmic | 0:211f27847e85 | 662 | { |
pmic | 0:211f27847e85 | 663 | case 500: |
pmic | 0:211f27847e85 | 664 | ctrl1RegValue |= (0x1 << 3); |
pmic | 0:211f27847e85 | 665 | settings.gyro.scale = 500; |
pmic | 0:211f27847e85 | 666 | break; |
pmic | 0:211f27847e85 | 667 | case 2000: |
pmic | 0:211f27847e85 | 668 | ctrl1RegValue |= (0x3 << 3); |
pmic | 0:211f27847e85 | 669 | settings.gyro.scale = 2000; |
pmic | 0:211f27847e85 | 670 | break; |
pmic | 0:211f27847e85 | 671 | default: // Otherwise we'll set it to 245 dps (0x0 << 4) |
pmic | 0:211f27847e85 | 672 | settings.gyro.scale = 245; |
pmic | 0:211f27847e85 | 673 | break; |
pmic | 0:211f27847e85 | 674 | } |
pmic | 0:211f27847e85 | 675 | xgWriteByte(CTRL_REG1_G, ctrl1RegValue); |
pmic | 0:211f27847e85 | 676 | |
pmic | 0:211f27847e85 | 677 | calcgRes(); |
pmic | 0:211f27847e85 | 678 | } |
pmic | 0:211f27847e85 | 679 | |
pmic | 0:211f27847e85 | 680 | void LSM9DS1::setAccelScale(uint8_t aScl) |
pmic | 0:211f27847e85 | 681 | { |
pmic | 0:211f27847e85 | 682 | // We need to preserve the other bytes in CTRL_REG6_XL. So, first read it: |
pmic | 0:211f27847e85 | 683 | uint8_t tempRegValue = xgReadByte(CTRL_REG6_XL); |
pmic | 0:211f27847e85 | 684 | // Mask out accel scale bits: |
pmic | 0:211f27847e85 | 685 | tempRegValue &= 0xE7; |
pmic | 0:211f27847e85 | 686 | |
pmic | 0:211f27847e85 | 687 | switch (aScl) |
pmic | 0:211f27847e85 | 688 | { |
pmic | 0:211f27847e85 | 689 | case 4: |
pmic | 0:211f27847e85 | 690 | tempRegValue |= (0x2 << 3); |
pmic | 0:211f27847e85 | 691 | settings.accel.scale = 4; |
pmic | 0:211f27847e85 | 692 | break; |
pmic | 0:211f27847e85 | 693 | case 8: |
pmic | 0:211f27847e85 | 694 | tempRegValue |= (0x3 << 3); |
pmic | 0:211f27847e85 | 695 | settings.accel.scale = 8; |
pmic | 0:211f27847e85 | 696 | break; |
pmic | 0:211f27847e85 | 697 | case 16: |
pmic | 0:211f27847e85 | 698 | tempRegValue |= (0x1 << 3); |
pmic | 0:211f27847e85 | 699 | settings.accel.scale = 16; |
pmic | 0:211f27847e85 | 700 | break; |
pmic | 0:211f27847e85 | 701 | default: // Otherwise it'll be set to 2g (0x0 << 3) |
pmic | 0:211f27847e85 | 702 | settings.accel.scale = 2; |
pmic | 0:211f27847e85 | 703 | break; |
pmic | 0:211f27847e85 | 704 | } |
pmic | 0:211f27847e85 | 705 | xgWriteByte(CTRL_REG6_XL, tempRegValue); |
pmic | 0:211f27847e85 | 706 | |
pmic | 0:211f27847e85 | 707 | // Then calculate a new aRes, which relies on aScale being set correctly: |
pmic | 0:211f27847e85 | 708 | calcaRes(); |
pmic | 0:211f27847e85 | 709 | } |
pmic | 0:211f27847e85 | 710 | |
pmic | 0:211f27847e85 | 711 | void LSM9DS1::setMagScale(uint8_t mScl) |
pmic | 0:211f27847e85 | 712 | { |
pmic | 0:211f27847e85 | 713 | // We need to preserve the other bytes in CTRL_REG6_XM. So, first read it: |
pmic | 0:211f27847e85 | 714 | uint8_t temp = mReadByte(CTRL_REG2_M); |
pmic | 0:211f27847e85 | 715 | // Then mask out the mag scale bits: |
pmic | 0:211f27847e85 | 716 | temp &= 0xFF^(0x3 << 5); |
pmic | 0:211f27847e85 | 717 | |
pmic | 0:211f27847e85 | 718 | switch (mScl) |
pmic | 0:211f27847e85 | 719 | { |
pmic | 0:211f27847e85 | 720 | case 8: |
pmic | 0:211f27847e85 | 721 | temp |= (0x1 << 5); |
pmic | 0:211f27847e85 | 722 | settings.mag.scale = 8; |
pmic | 0:211f27847e85 | 723 | break; |
pmic | 0:211f27847e85 | 724 | case 12: |
pmic | 0:211f27847e85 | 725 | temp |= (0x2 << 5); |
pmic | 0:211f27847e85 | 726 | settings.mag.scale = 12; |
pmic | 0:211f27847e85 | 727 | break; |
pmic | 0:211f27847e85 | 728 | case 16: |
pmic | 0:211f27847e85 | 729 | temp |= (0x3 << 5); |
pmic | 0:211f27847e85 | 730 | settings.mag.scale = 16; |
pmic | 0:211f27847e85 | 731 | break; |
pmic | 0:211f27847e85 | 732 | default: // Otherwise we'll default to 4 gauss (00) |
pmic | 0:211f27847e85 | 733 | settings.mag.scale = 4; |
pmic | 0:211f27847e85 | 734 | break; |
pmic | 0:211f27847e85 | 735 | } |
pmic | 0:211f27847e85 | 736 | |
pmic | 0:211f27847e85 | 737 | // And write the new register value back into CTRL_REG6_XM: |
pmic | 0:211f27847e85 | 738 | mWriteByte(CTRL_REG2_M, temp); |
pmic | 0:211f27847e85 | 739 | |
pmic | 0:211f27847e85 | 740 | // We've updated the sensor, but we also need to update our class variables |
pmic | 0:211f27847e85 | 741 | // First update mScale: |
pmic | 0:211f27847e85 | 742 | //mScale = mScl; |
pmic | 0:211f27847e85 | 743 | // Then calculate a new mRes, which relies on mScale being set correctly: |
pmic | 0:211f27847e85 | 744 | calcmRes(); |
pmic | 0:211f27847e85 | 745 | } |
pmic | 0:211f27847e85 | 746 | |
pmic | 0:211f27847e85 | 747 | void LSM9DS1::setGyroODR(uint8_t gRate) |
pmic | 0:211f27847e85 | 748 | { |
pmic | 0:211f27847e85 | 749 | // Only do this if gRate is not 0 (which would disable the gyro) |
pmic | 0:211f27847e85 | 750 | if ((gRate & 0x07) != 0) |
pmic | 0:211f27847e85 | 751 | { |
pmic | 0:211f27847e85 | 752 | // We need to preserve the other bytes in CTRL_REG1_G. So, first read it: |
pmic | 0:211f27847e85 | 753 | uint8_t temp = xgReadByte(CTRL_REG1_G); |
pmic | 0:211f27847e85 | 754 | // Then mask out the gyro ODR bits: |
pmic | 0:211f27847e85 | 755 | temp &= 0xFF^(0x7 << 5); |
pmic | 0:211f27847e85 | 756 | temp |= (gRate & 0x07) << 5; |
pmic | 0:211f27847e85 | 757 | // Update our settings struct |
pmic | 0:211f27847e85 | 758 | settings.gyro.sampleRate = gRate & 0x07; |
pmic | 0:211f27847e85 | 759 | // And write the new register value back into CTRL_REG1_G: |
pmic | 0:211f27847e85 | 760 | xgWriteByte(CTRL_REG1_G, temp); |
pmic | 0:211f27847e85 | 761 | } |
pmic | 0:211f27847e85 | 762 | } |
pmic | 0:211f27847e85 | 763 | |
pmic | 0:211f27847e85 | 764 | void LSM9DS1::setAccelODR(uint8_t aRate) |
pmic | 0:211f27847e85 | 765 | { |
pmic | 0:211f27847e85 | 766 | // Only do this if aRate is not 0 (which would disable the accel) |
pmic | 0:211f27847e85 | 767 | if ((aRate & 0x07) != 0) |
pmic | 0:211f27847e85 | 768 | { |
pmic | 0:211f27847e85 | 769 | // We need to preserve the other bytes in CTRL_REG1_XM. So, first read it: |
pmic | 0:211f27847e85 | 770 | uint8_t temp = xgReadByte(CTRL_REG6_XL); |
pmic | 0:211f27847e85 | 771 | // Then mask out the accel ODR bits: |
pmic | 0:211f27847e85 | 772 | temp &= 0x1F; |
pmic | 0:211f27847e85 | 773 | // Then shift in our new ODR bits: |
pmic | 0:211f27847e85 | 774 | temp |= ((aRate & 0x07) << 5); |
pmic | 0:211f27847e85 | 775 | settings.accel.sampleRate = aRate & 0x07; |
pmic | 0:211f27847e85 | 776 | // And write the new register value back into CTRL_REG1_XM: |
pmic | 0:211f27847e85 | 777 | xgWriteByte(CTRL_REG6_XL, temp); |
pmic | 0:211f27847e85 | 778 | } |
pmic | 0:211f27847e85 | 779 | } |
pmic | 0:211f27847e85 | 780 | |
pmic | 0:211f27847e85 | 781 | void LSM9DS1::setMagODR(uint8_t mRate) |
pmic | 0:211f27847e85 | 782 | { |
pmic | 0:211f27847e85 | 783 | // We need to preserve the other bytes in CTRL_REG5_XM. So, first read it: |
pmic | 0:211f27847e85 | 784 | uint8_t temp = mReadByte(CTRL_REG1_M); |
pmic | 0:211f27847e85 | 785 | // Then mask out the mag ODR bits: |
pmic | 0:211f27847e85 | 786 | temp &= 0xFF^(0x7 << 2); |
pmic | 0:211f27847e85 | 787 | // Then shift in our new ODR bits: |
pmic | 0:211f27847e85 | 788 | temp |= ((mRate & 0x07) << 2); |
pmic | 0:211f27847e85 | 789 | settings.mag.sampleRate = mRate & 0x07; |
pmic | 0:211f27847e85 | 790 | // And write the new register value back into CTRL_REG5_XM: |
pmic | 0:211f27847e85 | 791 | mWriteByte(CTRL_REG1_M, temp); |
pmic | 0:211f27847e85 | 792 | } |
pmic | 0:211f27847e85 | 793 | |
pmic | 0:211f27847e85 | 794 | void LSM9DS1::calcgRes() |
pmic | 0:211f27847e85 | 795 | { |
pmic | 0:211f27847e85 | 796 | gRes = ((float) settings.gyro.scale) / 32768.0f; |
pmic | 0:211f27847e85 | 797 | } |
pmic | 0:211f27847e85 | 798 | |
pmic | 0:211f27847e85 | 799 | void LSM9DS1::calcaRes() |
pmic | 0:211f27847e85 | 800 | { |
pmic | 0:211f27847e85 | 801 | aRes = ((float) settings.accel.scale) / 32768.0f; |
pmic | 0:211f27847e85 | 802 | } |
pmic | 0:211f27847e85 | 803 | |
pmic | 0:211f27847e85 | 804 | void LSM9DS1::calcmRes() |
pmic | 0:211f27847e85 | 805 | { |
pmic | 0:211f27847e85 | 806 | //mRes = ((float) settings.mag.scale) / 32768.0; |
pmic | 0:211f27847e85 | 807 | switch (settings.mag.scale) |
pmic | 0:211f27847e85 | 808 | { |
pmic | 0:211f27847e85 | 809 | case 4: |
pmic | 0:211f27847e85 | 810 | mRes = magSensitivity[0]; |
pmic | 0:211f27847e85 | 811 | break; |
pmic | 0:211f27847e85 | 812 | case 8: |
pmic | 0:211f27847e85 | 813 | mRes = magSensitivity[1]; |
pmic | 0:211f27847e85 | 814 | break; |
pmic | 0:211f27847e85 | 815 | case 12: |
pmic | 0:211f27847e85 | 816 | mRes = magSensitivity[2]; |
pmic | 0:211f27847e85 | 817 | break; |
pmic | 0:211f27847e85 | 818 | case 16: |
pmic | 0:211f27847e85 | 819 | mRes = magSensitivity[3]; |
pmic | 0:211f27847e85 | 820 | break; |
pmic | 0:211f27847e85 | 821 | } |
pmic | 0:211f27847e85 | 822 | |
pmic | 0:211f27847e85 | 823 | } |
pmic | 0:211f27847e85 | 824 | |
pmic | 0:211f27847e85 | 825 | void LSM9DS1::configInt(interrupt_select interrupt, uint8_t generator, |
pmic | 0:211f27847e85 | 826 | h_lactive activeLow, pp_od pushPull) |
pmic | 0:211f27847e85 | 827 | { |
pmic | 0:211f27847e85 | 828 | // Write to INT1_CTRL or INT2_CTRL. [interupt] should already be one of |
pmic | 0:211f27847e85 | 829 | // those two values. |
pmic | 0:211f27847e85 | 830 | // [generator] should be an OR'd list of values from the interrupt_generators enum |
pmic | 0:211f27847e85 | 831 | xgWriteByte(interrupt, generator); |
pmic | 0:211f27847e85 | 832 | |
pmic | 0:211f27847e85 | 833 | // Configure CTRL_REG8 |
pmic | 0:211f27847e85 | 834 | uint8_t temp; |
pmic | 0:211f27847e85 | 835 | temp = xgReadByte(CTRL_REG8); |
pmic | 0:211f27847e85 | 836 | |
pmic | 0:211f27847e85 | 837 | if (activeLow) temp |= (1<<5); |
pmic | 0:211f27847e85 | 838 | else temp &= ~(1<<5); |
pmic | 0:211f27847e85 | 839 | |
pmic | 0:211f27847e85 | 840 | if (pushPull) temp &= ~(1<<4); |
pmic | 0:211f27847e85 | 841 | else temp |= (1<<4); |
pmic | 0:211f27847e85 | 842 | |
pmic | 0:211f27847e85 | 843 | xgWriteByte(CTRL_REG8, temp); |
pmic | 0:211f27847e85 | 844 | } |
pmic | 0:211f27847e85 | 845 | |
pmic | 0:211f27847e85 | 846 | void LSM9DS1::configInactivity(uint8_t duration, uint8_t threshold, bool sleepOn) |
pmic | 0:211f27847e85 | 847 | { |
pmic | 0:211f27847e85 | 848 | uint8_t temp = 0; |
pmic | 0:211f27847e85 | 849 | |
pmic | 0:211f27847e85 | 850 | temp = threshold & 0x7F; |
pmic | 0:211f27847e85 | 851 | if (sleepOn) temp |= (1<<7); |
pmic | 0:211f27847e85 | 852 | xgWriteByte(ACT_THS, temp); |
pmic | 0:211f27847e85 | 853 | |
pmic | 0:211f27847e85 | 854 | xgWriteByte(ACT_DUR, duration); |
pmic | 0:211f27847e85 | 855 | } |
pmic | 0:211f27847e85 | 856 | |
pmic | 0:211f27847e85 | 857 | uint8_t LSM9DS1::getInactivity() |
pmic | 0:211f27847e85 | 858 | { |
pmic | 0:211f27847e85 | 859 | uint8_t temp = xgReadByte(STATUS_REG_0); |
pmic | 0:211f27847e85 | 860 | temp &= (0x10); |
pmic | 0:211f27847e85 | 861 | return temp; |
pmic | 0:211f27847e85 | 862 | } |
pmic | 0:211f27847e85 | 863 | |
pmic | 0:211f27847e85 | 864 | void LSM9DS1::configAccelInt(uint8_t generator, bool andInterrupts) |
pmic | 0:211f27847e85 | 865 | { |
pmic | 0:211f27847e85 | 866 | // Use variables from accel_interrupt_generator, OR'd together to create |
pmic | 0:211f27847e85 | 867 | // the [generator]value. |
pmic | 0:211f27847e85 | 868 | uint8_t temp = generator; |
pmic | 0:211f27847e85 | 869 | if (andInterrupts) temp |= 0x80; |
pmic | 0:211f27847e85 | 870 | xgWriteByte(INT_GEN_CFG_XL, temp); |
pmic | 0:211f27847e85 | 871 | } |
pmic | 0:211f27847e85 | 872 | |
pmic | 0:211f27847e85 | 873 | void LSM9DS1::configAccelThs(uint8_t threshold, lsm9ds1_axis axis, uint8_t duration, bool wait) |
pmic | 0:211f27847e85 | 874 | { |
pmic | 0:211f27847e85 | 875 | // Write threshold value to INT_GEN_THS_?_XL. |
pmic | 0:211f27847e85 | 876 | // axis will be 0, 1, or 2 (x, y, z respectively) |
pmic | 0:211f27847e85 | 877 | xgWriteByte(INT_GEN_THS_X_XL + axis, threshold); |
pmic | 0:211f27847e85 | 878 | |
pmic | 0:211f27847e85 | 879 | // Write duration and wait to INT_GEN_DUR_XL |
pmic | 0:211f27847e85 | 880 | uint8_t temp; |
pmic | 0:211f27847e85 | 881 | temp = (duration & 0x7F); |
pmic | 0:211f27847e85 | 882 | if (wait) temp |= 0x80; |
pmic | 0:211f27847e85 | 883 | xgWriteByte(INT_GEN_DUR_XL, temp); |
pmic | 0:211f27847e85 | 884 | } |
pmic | 0:211f27847e85 | 885 | |
pmic | 0:211f27847e85 | 886 | uint8_t LSM9DS1::getAccelIntSrc() |
pmic | 0:211f27847e85 | 887 | { |
pmic | 0:211f27847e85 | 888 | uint8_t intSrc = xgReadByte(INT_GEN_SRC_XL); |
pmic | 0:211f27847e85 | 889 | |
pmic | 0:211f27847e85 | 890 | // Check if the IA_XL (interrupt active) bit is set |
pmic | 0:211f27847e85 | 891 | if (intSrc & (1<<6)) |
pmic | 0:211f27847e85 | 892 | { |
pmic | 0:211f27847e85 | 893 | return (intSrc & 0x3F); |
pmic | 0:211f27847e85 | 894 | } |
pmic | 0:211f27847e85 | 895 | |
pmic | 0:211f27847e85 | 896 | return 0; |
pmic | 0:211f27847e85 | 897 | } |
pmic | 0:211f27847e85 | 898 | |
pmic | 0:211f27847e85 | 899 | void LSM9DS1::configGyroInt(uint8_t generator, bool aoi, bool latch) |
pmic | 0:211f27847e85 | 900 | { |
pmic | 0:211f27847e85 | 901 | // Use variables from accel_interrupt_generator, OR'd together to create |
pmic | 0:211f27847e85 | 902 | // the [generator]value. |
pmic | 0:211f27847e85 | 903 | uint8_t temp = generator; |
pmic | 0:211f27847e85 | 904 | if (aoi) temp |= 0x80; |
pmic | 0:211f27847e85 | 905 | if (latch) temp |= 0x40; |
pmic | 0:211f27847e85 | 906 | xgWriteByte(INT_GEN_CFG_G, temp); |
pmic | 0:211f27847e85 | 907 | } |
pmic | 0:211f27847e85 | 908 | |
pmic | 0:211f27847e85 | 909 | void LSM9DS1::configGyroThs(int16_t threshold, lsm9ds1_axis axis, uint8_t duration, bool wait) |
pmic | 0:211f27847e85 | 910 | { |
pmic | 0:211f27847e85 | 911 | uint8_t buffer[2]; |
pmic | 0:211f27847e85 | 912 | buffer[0] = (threshold & 0x7F00) >> 8; |
pmic | 0:211f27847e85 | 913 | buffer[1] = (threshold & 0x00FF); |
pmic | 0:211f27847e85 | 914 | // Write threshold value to INT_GEN_THS_?H_G and INT_GEN_THS_?L_G. |
pmic | 0:211f27847e85 | 915 | // axis will be 0, 1, or 2 (x, y, z respectively) |
pmic | 0:211f27847e85 | 916 | xgWriteByte(INT_GEN_THS_XH_G + (axis * 2), buffer[0]); |
pmic | 0:211f27847e85 | 917 | xgWriteByte(INT_GEN_THS_XH_G + 1 + (axis * 2), buffer[1]); |
pmic | 0:211f27847e85 | 918 | |
pmic | 0:211f27847e85 | 919 | // Write duration and wait to INT_GEN_DUR_XL |
pmic | 0:211f27847e85 | 920 | uint8_t temp; |
pmic | 0:211f27847e85 | 921 | temp = (duration & 0x7F); |
pmic | 0:211f27847e85 | 922 | if (wait) temp |= 0x80; |
pmic | 0:211f27847e85 | 923 | xgWriteByte(INT_GEN_DUR_G, temp); |
pmic | 0:211f27847e85 | 924 | } |
pmic | 0:211f27847e85 | 925 | |
pmic | 0:211f27847e85 | 926 | uint8_t LSM9DS1::getGyroIntSrc() |
pmic | 0:211f27847e85 | 927 | { |
pmic | 0:211f27847e85 | 928 | uint8_t intSrc = xgReadByte(INT_GEN_SRC_G); |
pmic | 0:211f27847e85 | 929 | |
pmic | 0:211f27847e85 | 930 | // Check if the IA_G (interrupt active) bit is set |
pmic | 0:211f27847e85 | 931 | if (intSrc & (1<<6)) |
pmic | 0:211f27847e85 | 932 | { |
pmic | 0:211f27847e85 | 933 | return (intSrc & 0x3F); |
pmic | 0:211f27847e85 | 934 | } |
pmic | 0:211f27847e85 | 935 | |
pmic | 0:211f27847e85 | 936 | return 0; |
pmic | 0:211f27847e85 | 937 | } |
pmic | 0:211f27847e85 | 938 | |
pmic | 0:211f27847e85 | 939 | void LSM9DS1::configMagInt(uint8_t generator, h_lactive activeLow, bool latch) |
pmic | 0:211f27847e85 | 940 | { |
pmic | 0:211f27847e85 | 941 | // Mask out non-generator bits (0-4) |
pmic | 0:211f27847e85 | 942 | uint8_t config = (generator & 0xE0); |
pmic | 0:211f27847e85 | 943 | // IEA bit is 0 for active-low, 1 for active-high. |
pmic | 0:211f27847e85 | 944 | if (activeLow == INT_ACTIVE_HIGH) config |= (1<<2); |
pmic | 0:211f27847e85 | 945 | // IEL bit is 0 for latched, 1 for not-latched |
pmic | 0:211f27847e85 | 946 | if (!latch) config |= (1<<1); |
pmic | 0:211f27847e85 | 947 | // As long as we have at least 1 generator, enable the interrupt |
pmic | 0:211f27847e85 | 948 | if (generator != 0) config |= (1<<0); |
pmic | 0:211f27847e85 | 949 | |
pmic | 0:211f27847e85 | 950 | mWriteByte(INT_CFG_M, config); |
pmic | 0:211f27847e85 | 951 | } |
pmic | 0:211f27847e85 | 952 | |
pmic | 0:211f27847e85 | 953 | void LSM9DS1::configMagThs(uint16_t threshold) |
pmic | 0:211f27847e85 | 954 | { |
pmic | 0:211f27847e85 | 955 | // Write high eight bits of [threshold] to INT_THS_H_M |
pmic | 0:211f27847e85 | 956 | mWriteByte(INT_THS_H_M, uint8_t((threshold & 0x7F00) >> 8)); |
pmic | 0:211f27847e85 | 957 | // Write low eight bits of [threshold] to INT_THS_L_M |
pmic | 0:211f27847e85 | 958 | mWriteByte(INT_THS_L_M, uint8_t(threshold & 0x00FF)); |
pmic | 0:211f27847e85 | 959 | } |
pmic | 0:211f27847e85 | 960 | |
pmic | 0:211f27847e85 | 961 | uint8_t LSM9DS1::getMagIntSrc() |
pmic | 0:211f27847e85 | 962 | { |
pmic | 0:211f27847e85 | 963 | uint8_t intSrc = mReadByte(INT_SRC_M); |
pmic | 0:211f27847e85 | 964 | |
pmic | 0:211f27847e85 | 965 | // Check if the INT (interrupt active) bit is set |
pmic | 0:211f27847e85 | 966 | if (intSrc & (1<<0)) |
pmic | 0:211f27847e85 | 967 | { |
pmic | 0:211f27847e85 | 968 | return (intSrc & 0xFE); |
pmic | 0:211f27847e85 | 969 | } |
pmic | 0:211f27847e85 | 970 | |
pmic | 0:211f27847e85 | 971 | return 0; |
pmic | 0:211f27847e85 | 972 | } |
pmic | 0:211f27847e85 | 973 | |
pmic | 0:211f27847e85 | 974 | void LSM9DS1::sleepGyro(bool enable) |
pmic | 0:211f27847e85 | 975 | { |
pmic | 0:211f27847e85 | 976 | uint8_t temp = xgReadByte(CTRL_REG9); |
pmic | 0:211f27847e85 | 977 | if (enable) temp |= (1<<6); |
pmic | 0:211f27847e85 | 978 | else temp &= ~(1<<6); |
pmic | 0:211f27847e85 | 979 | xgWriteByte(CTRL_REG9, temp); |
pmic | 0:211f27847e85 | 980 | } |
pmic | 0:211f27847e85 | 981 | |
pmic | 0:211f27847e85 | 982 | void LSM9DS1::enableFIFO(bool enable) |
pmic | 0:211f27847e85 | 983 | { |
pmic | 0:211f27847e85 | 984 | uint8_t temp = xgReadByte(CTRL_REG9); |
pmic | 0:211f27847e85 | 985 | if (enable) temp |= (1<<1); |
pmic | 0:211f27847e85 | 986 | else temp &= ~(1<<1); |
pmic | 0:211f27847e85 | 987 | xgWriteByte(CTRL_REG9, temp); |
pmic | 0:211f27847e85 | 988 | } |
pmic | 0:211f27847e85 | 989 | |
pmic | 0:211f27847e85 | 990 | void LSM9DS1::setFIFO(fifoMode_type fifoMode, uint8_t fifoThs) |
pmic | 0:211f27847e85 | 991 | { |
pmic | 0:211f27847e85 | 992 | // Limit threshold - 0x1F (31) is the maximum. If more than that was asked |
pmic | 0:211f27847e85 | 993 | // limit it to the maximum. |
pmic | 0:211f27847e85 | 994 | uint8_t threshold = fifoThs <= 0x1F ? fifoThs : 0x1F; |
pmic | 0:211f27847e85 | 995 | xgWriteByte(FIFO_CTRL, ((fifoMode & 0x7) << 5) | (threshold & 0x1F)); |
pmic | 0:211f27847e85 | 996 | } |
pmic | 0:211f27847e85 | 997 | |
pmic | 0:211f27847e85 | 998 | uint8_t LSM9DS1::getFIFOSamples() |
pmic | 0:211f27847e85 | 999 | { |
pmic | 0:211f27847e85 | 1000 | return (xgReadByte(FIFO_SRC) & 0x3F); |
pmic | 0:211f27847e85 | 1001 | } |
pmic | 0:211f27847e85 | 1002 | |
pmic | 0:211f27847e85 | 1003 | void LSM9DS1::constrainScales() |
pmic | 0:211f27847e85 | 1004 | { |
pmic | 0:211f27847e85 | 1005 | if ((settings.gyro.scale != 245) && (settings.gyro.scale != 500) && |
pmic | 0:211f27847e85 | 1006 | (settings.gyro.scale != 2000)) |
pmic | 0:211f27847e85 | 1007 | { |
pmic | 0:211f27847e85 | 1008 | settings.gyro.scale = 245; |
pmic | 0:211f27847e85 | 1009 | } |
pmic | 0:211f27847e85 | 1010 | |
pmic | 0:211f27847e85 | 1011 | if ((settings.accel.scale != 2) && (settings.accel.scale != 4) && |
pmic | 0:211f27847e85 | 1012 | (settings.accel.scale != 8) && (settings.accel.scale != 16)) |
pmic | 0:211f27847e85 | 1013 | { |
pmic | 0:211f27847e85 | 1014 | settings.accel.scale = 2; |
pmic | 0:211f27847e85 | 1015 | } |
pmic | 0:211f27847e85 | 1016 | |
pmic | 0:211f27847e85 | 1017 | if ((settings.mag.scale != 4) && (settings.mag.scale != 8) && |
pmic | 0:211f27847e85 | 1018 | (settings.mag.scale != 12) && (settings.mag.scale != 16)) |
pmic | 0:211f27847e85 | 1019 | { |
pmic | 0:211f27847e85 | 1020 | settings.mag.scale = 4; |
pmic | 0:211f27847e85 | 1021 | } |
pmic | 0:211f27847e85 | 1022 | } |
pmic | 0:211f27847e85 | 1023 | |
pmic | 0:211f27847e85 | 1024 | void LSM9DS1::xgWriteByte(uint8_t subAddress, uint8_t data) |
pmic | 0:211f27847e85 | 1025 | { |
pmic | 0:211f27847e85 | 1026 | // Whether we're using I2C or SPI, write a byte using the |
pmic | 0:211f27847e85 | 1027 | // gyro-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1028 | if (settings.device.commInterface == IMU_MODE_I2C) { |
pmic | 0:211f27847e85 | 1029 | printf("yo"); |
pmic | 0:211f27847e85 | 1030 | I2CwriteByte(_xgAddress, subAddress, data); |
pmic | 0:211f27847e85 | 1031 | } else if (settings.device.commInterface == IMU_MODE_SPI) { |
pmic | 0:211f27847e85 | 1032 | SPIwriteByte(_xgAddress, subAddress, data); |
pmic | 0:211f27847e85 | 1033 | } |
pmic | 0:211f27847e85 | 1034 | } |
pmic | 0:211f27847e85 | 1035 | |
pmic | 0:211f27847e85 | 1036 | void LSM9DS1::mWriteByte(uint8_t subAddress, uint8_t data) |
pmic | 0:211f27847e85 | 1037 | { |
pmic | 0:211f27847e85 | 1038 | // Whether we're using I2C or SPI, write a byte using the |
pmic | 0:211f27847e85 | 1039 | // accelerometer-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1040 | if (settings.device.commInterface == IMU_MODE_I2C) |
pmic | 0:211f27847e85 | 1041 | return I2CwriteByte(_mAddress, subAddress, data); |
pmic | 0:211f27847e85 | 1042 | else if (settings.device.commInterface == IMU_MODE_SPI) |
pmic | 0:211f27847e85 | 1043 | return SPIwriteByte(_mAddress, subAddress, data); |
pmic | 0:211f27847e85 | 1044 | } |
pmic | 0:211f27847e85 | 1045 | |
pmic | 0:211f27847e85 | 1046 | uint8_t LSM9DS1::xgReadByte(uint8_t subAddress) |
pmic | 0:211f27847e85 | 1047 | { |
pmic | 0:211f27847e85 | 1048 | // Whether we're using I2C or SPI, read a byte using the |
pmic | 0:211f27847e85 | 1049 | // gyro-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1050 | |
pmic | 0:211f27847e85 | 1051 | if (settings.device.commInterface == IMU_MODE_I2C) |
pmic | 0:211f27847e85 | 1052 | return I2CreadByte(_xgAddress, subAddress); |
pmic | 0:211f27847e85 | 1053 | else if (settings.device.commInterface == IMU_MODE_SPI) |
pmic | 0:211f27847e85 | 1054 | return SPIreadByte(_xgAddress, subAddress); |
pmic | 0:211f27847e85 | 1055 | else |
pmic | 0:211f27847e85 | 1056 | return 0; |
pmic | 0:211f27847e85 | 1057 | } |
pmic | 0:211f27847e85 | 1058 | |
pmic | 0:211f27847e85 | 1059 | void LSM9DS1::xgReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) |
pmic | 0:211f27847e85 | 1060 | { |
pmic | 0:211f27847e85 | 1061 | // Whether we're using I2C or SPI, read multiple bytes using the |
pmic | 0:211f27847e85 | 1062 | // gyro-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1063 | if (settings.device.commInterface == IMU_MODE_I2C) { |
pmic | 0:211f27847e85 | 1064 | I2CreadBytes(_xgAddress, subAddress, dest, count); |
pmic | 0:211f27847e85 | 1065 | } else if (settings.device.commInterface == IMU_MODE_SPI) { |
pmic | 0:211f27847e85 | 1066 | SPIreadBytes(_xgAddress, subAddress, dest, count); |
pmic | 0:211f27847e85 | 1067 | } |
pmic | 0:211f27847e85 | 1068 | } |
pmic | 0:211f27847e85 | 1069 | |
pmic | 0:211f27847e85 | 1070 | uint8_t LSM9DS1::mReadByte(uint8_t subAddress) |
pmic | 0:211f27847e85 | 1071 | { |
pmic | 0:211f27847e85 | 1072 | // Whether we're using I2C or SPI, read a byte using the |
pmic | 0:211f27847e85 | 1073 | // accelerometer-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1074 | if (settings.device.commInterface == IMU_MODE_I2C) |
pmic | 0:211f27847e85 | 1075 | return I2CreadByte(_mAddress, subAddress); |
pmic | 0:211f27847e85 | 1076 | else if (settings.device.commInterface == IMU_MODE_SPI) |
pmic | 0:211f27847e85 | 1077 | return SPIreadByte(_mAddress, subAddress); |
pmic | 0:211f27847e85 | 1078 | else |
pmic | 0:211f27847e85 | 1079 | return 0; |
pmic | 0:211f27847e85 | 1080 | } |
pmic | 0:211f27847e85 | 1081 | |
pmic | 0:211f27847e85 | 1082 | void LSM9DS1::mReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) |
pmic | 0:211f27847e85 | 1083 | { |
pmic | 0:211f27847e85 | 1084 | // Whether we're using I2C or SPI, read multiple bytes using the |
pmic | 0:211f27847e85 | 1085 | // accelerometer-specific I2C address or SPI CS pin. |
pmic | 0:211f27847e85 | 1086 | if (settings.device.commInterface == IMU_MODE_I2C) |
pmic | 0:211f27847e85 | 1087 | I2CreadBytes(_mAddress, subAddress, dest, count); |
pmic | 0:211f27847e85 | 1088 | else if (settings.device.commInterface == IMU_MODE_SPI) |
pmic | 0:211f27847e85 | 1089 | SPIreadBytes(_mAddress, subAddress, dest, count); |
pmic | 0:211f27847e85 | 1090 | } |
pmic | 0:211f27847e85 | 1091 | |
pmic | 0:211f27847e85 | 1092 | void LSM9DS1::initSPI() |
pmic | 0:211f27847e85 | 1093 | { |
pmic | 0:211f27847e85 | 1094 | /* |
pmic | 0:211f27847e85 | 1095 | pinMode(_xgAddress, OUTPUT); |
pmic | 0:211f27847e85 | 1096 | digitalWrite(_xgAddress, HIGH); |
pmic | 0:211f27847e85 | 1097 | pinMode(_mAddress, OUTPUT); |
pmic | 0:211f27847e85 | 1098 | digitalWrite(_mAddress, HIGH); |
pmic | 0:211f27847e85 | 1099 | |
pmic | 0:211f27847e85 | 1100 | SPI.begin(); |
pmic | 0:211f27847e85 | 1101 | // Maximum SPI frequency is 10MHz, could divide by 2 here: |
pmic | 0:211f27847e85 | 1102 | SPI.setClockDivider(SPI_CLOCK_DIV2); |
pmic | 0:211f27847e85 | 1103 | // Data is read and written MSb first. |
pmic | 0:211f27847e85 | 1104 | SPI.setBitOrder(MSBFIRST); |
pmic | 0:211f27847e85 | 1105 | // Data is captured on rising edge of clock (CPHA = 0) |
pmic | 0:211f27847e85 | 1106 | // Base value of the clock is HIGH (CPOL = 1) |
pmic | 0:211f27847e85 | 1107 | SPI.setDataMode(SPI_MODE0); |
pmic | 0:211f27847e85 | 1108 | */ |
pmic | 0:211f27847e85 | 1109 | } |
pmic | 0:211f27847e85 | 1110 | |
pmic | 0:211f27847e85 | 1111 | void LSM9DS1::SPIwriteByte(uint8_t csPin, uint8_t subAddress, uint8_t data) |
pmic | 0:211f27847e85 | 1112 | { |
pmic | 0:211f27847e85 | 1113 | /* |
pmic | 0:211f27847e85 | 1114 | digitalWrite(csPin, LOW); // Initiate communication |
pmic | 0:211f27847e85 | 1115 | |
pmic | 0:211f27847e85 | 1116 | // If write, bit 0 (MSB) should be 0 |
pmic | 0:211f27847e85 | 1117 | // If single write, bit 1 should be 0 |
pmic | 0:211f27847e85 | 1118 | SPI.transfer(subAddress & 0x3F); // Send Address |
pmic | 0:211f27847e85 | 1119 | SPI.transfer(data); // Send data |
pmic | 0:211f27847e85 | 1120 | |
pmic | 0:211f27847e85 | 1121 | digitalWrite(csPin, HIGH); // Close communication |
pmic | 0:211f27847e85 | 1122 | */ |
pmic | 0:211f27847e85 | 1123 | } |
pmic | 0:211f27847e85 | 1124 | |
pmic | 0:211f27847e85 | 1125 | uint8_t LSM9DS1::SPIreadByte(uint8_t csPin, uint8_t subAddress) |
pmic | 0:211f27847e85 | 1126 | { |
pmic | 0:211f27847e85 | 1127 | uint8_t temp; |
pmic | 0:211f27847e85 | 1128 | // Use the multiple read function to read 1 byte. |
pmic | 0:211f27847e85 | 1129 | // Value is returned to `temp`. |
pmic | 0:211f27847e85 | 1130 | SPIreadBytes(csPin, subAddress, &temp, 1); |
pmic | 0:211f27847e85 | 1131 | return temp; |
pmic | 0:211f27847e85 | 1132 | } |
pmic | 0:211f27847e85 | 1133 | |
pmic | 0:211f27847e85 | 1134 | void LSM9DS1::SPIreadBytes(uint8_t csPin, uint8_t subAddress, |
pmic | 0:211f27847e85 | 1135 | uint8_t * dest, uint8_t count) |
pmic | 0:211f27847e85 | 1136 | { |
pmic | 0:211f27847e85 | 1137 | // To indicate a read, set bit 0 (msb) of first byte to 1 |
pmic | 0:211f27847e85 | 1138 | uint8_t rAddress = 0x80 | (subAddress & 0x3F); |
pmic | 0:211f27847e85 | 1139 | // Mag SPI port is different. If we're reading multiple bytes, |
pmic | 0:211f27847e85 | 1140 | // set bit 1 to 1. The remaining six bytes are the address to be read |
pmic | 0:211f27847e85 | 1141 | if ((csPin == _mAddress) && count > 1) |
pmic | 0:211f27847e85 | 1142 | rAddress |= 0x40; |
pmic | 0:211f27847e85 | 1143 | |
pmic | 0:211f27847e85 | 1144 | /* |
pmic | 0:211f27847e85 | 1145 | digitalWrite(csPin, LOW); // Initiate communication |
pmic | 0:211f27847e85 | 1146 | SPI.transfer(rAddress); |
pmic | 0:211f27847e85 | 1147 | for (int i=0; i<count; i++) |
pmic | 0:211f27847e85 | 1148 | { |
pmic | 0:211f27847e85 | 1149 | dest[i] = SPI.transfer(0x00); // Read into destination array |
pmic | 0:211f27847e85 | 1150 | } |
pmic | 0:211f27847e85 | 1151 | digitalWrite(csPin, HIGH); // Close communication |
pmic | 0:211f27847e85 | 1152 | */ |
pmic | 0:211f27847e85 | 1153 | } |
pmic | 0:211f27847e85 | 1154 | |
pmic | 0:211f27847e85 | 1155 | void LSM9DS1::initI2C() |
pmic | 0:211f27847e85 | 1156 | { |
pmic | 0:211f27847e85 | 1157 | /* |
pmic | 0:211f27847e85 | 1158 | Wire.begin(); // Initialize I2C library |
pmic | 0:211f27847e85 | 1159 | */ |
pmic | 0:211f27847e85 | 1160 | |
pmic | 0:211f27847e85 | 1161 | //already initialized in constructor! |
pmic | 0:211f27847e85 | 1162 | } |
pmic | 0:211f27847e85 | 1163 | |
pmic | 0:211f27847e85 | 1164 | // Wire.h read and write protocols |
pmic | 0:211f27847e85 | 1165 | void LSM9DS1::I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data) |
pmic | 0:211f27847e85 | 1166 | { |
pmic | 0:211f27847e85 | 1167 | /* |
pmic | 0:211f27847e85 | 1168 | Wire.beginTransmission(address); // Initialize the Tx buffer |
pmic | 0:211f27847e85 | 1169 | Wire.write(subAddress); // Put slave register address in Tx buffer |
pmic | 0:211f27847e85 | 1170 | Wire.write(data); // Put data in Tx buffer |
pmic | 0:211f27847e85 | 1171 | Wire.endTransmission(); // Send the Tx buffer |
pmic | 0:211f27847e85 | 1172 | */ |
pmic | 0:211f27847e85 | 1173 | char temp_data[2] = {subAddress, data}; |
pmic | 0:211f27847e85 | 1174 | i2c.write(address, temp_data, 2); |
pmic | 0:211f27847e85 | 1175 | } |
pmic | 0:211f27847e85 | 1176 | |
pmic | 0:211f27847e85 | 1177 | uint8_t LSM9DS1::I2CreadByte(uint8_t address, uint8_t subAddress) |
pmic | 0:211f27847e85 | 1178 | { |
pmic | 0:211f27847e85 | 1179 | /* |
pmic | 0:211f27847e85 | 1180 | int timeout = LSM9DS1_COMMUNICATION_TIMEOUT; |
pmic | 0:211f27847e85 | 1181 | uint8_t data; // `data` will store the register data |
pmic | 0:211f27847e85 | 1182 | |
pmic | 0:211f27847e85 | 1183 | Wire.beginTransmission(address); // Initialize the Tx buffer |
pmic | 0:211f27847e85 | 1184 | Wire.write(subAddress); // Put slave register address in Tx buffer |
pmic | 0:211f27847e85 | 1185 | Wire.endTransmission(true); // Send the Tx buffer, but send a restart to keep connection alive |
pmic | 0:211f27847e85 | 1186 | Wire.requestFrom(address, (uint8_t) 1); // Read one byte from slave register address |
pmic | 0:211f27847e85 | 1187 | while ((Wire.available() < 1) && (timeout-- > 0)) |
pmic | 0:211f27847e85 | 1188 | delay(1); |
pmic | 0:211f27847e85 | 1189 | |
pmic | 0:211f27847e85 | 1190 | if (timeout <= 0) |
pmic | 0:211f27847e85 | 1191 | return 255; //! Bad! 255 will be misinterpreted as a good value. |
pmic | 0:211f27847e85 | 1192 | |
pmic | 0:211f27847e85 | 1193 | data = Wire.read(); // Fill Rx buffer with result |
pmic | 0:211f27847e85 | 1194 | return data; // Return data read from slave register |
pmic | 0:211f27847e85 | 1195 | */ |
pmic | 0:211f27847e85 | 1196 | char data; |
pmic | 0:211f27847e85 | 1197 | char temp[1] = {subAddress}; |
pmic | 0:211f27847e85 | 1198 | |
pmic | 0:211f27847e85 | 1199 | i2c.write(address, temp, 1); |
pmic | 0:211f27847e85 | 1200 | //i2c.write(address & 0xFE); |
pmic | 0:211f27847e85 | 1201 | temp[0] = 0x00; |
pmic | 0:211f27847e85 | 1202 | i2c.write(address, temp, 1); |
pmic | 0:211f27847e85 | 1203 | //i2c.write( address | 0x01); |
pmic | 0:211f27847e85 | 1204 | int a = i2c.read(address, &data, 1); |
pmic | 0:211f27847e85 | 1205 | return data; |
pmic | 0:211f27847e85 | 1206 | } |
pmic | 0:211f27847e85 | 1207 | |
pmic | 0:211f27847e85 | 1208 | uint8_t LSM9DS1::I2CreadBytes(uint8_t address, uint8_t subAddress, uint8_t * dest, uint8_t count) |
pmic | 0:211f27847e85 | 1209 | { |
pmic | 0:211f27847e85 | 1210 | /* |
pmic | 0:211f27847e85 | 1211 | int timeout = LSM9DS1_COMMUNICATION_TIMEOUT; |
pmic | 0:211f27847e85 | 1212 | Wire.beginTransmission(address); // Initialize the Tx buffer |
pmic | 0:211f27847e85 | 1213 | // Next send the register to be read. OR with 0x80 to indicate multi-read. |
pmic | 0:211f27847e85 | 1214 | Wire.write(subAddress | 0x80); // Put slave register address in Tx buffer |
pmic | 0:211f27847e85 | 1215 | |
pmic | 0:211f27847e85 | 1216 | Wire.endTransmission(true); // Send the Tx buffer, but send a restart to keep connection alive |
pmic | 0:211f27847e85 | 1217 | uint8_t i = 0; |
pmic | 0:211f27847e85 | 1218 | Wire.requestFrom(address, count); // Read bytes from slave register address |
pmic | 0:211f27847e85 | 1219 | while ((Wire.available() < count) && (timeout-- > 0)) |
pmic | 0:211f27847e85 | 1220 | delay(1); |
pmic | 0:211f27847e85 | 1221 | if (timeout <= 0) |
pmic | 0:211f27847e85 | 1222 | return -1; |
pmic | 0:211f27847e85 | 1223 | |
pmic | 0:211f27847e85 | 1224 | for (int i=0; i<count;) |
pmic | 0:211f27847e85 | 1225 | { |
pmic | 0:211f27847e85 | 1226 | if (Wire.available()) |
pmic | 0:211f27847e85 | 1227 | { |
pmic | 0:211f27847e85 | 1228 | dest[i++] = Wire.read(); |
pmic | 0:211f27847e85 | 1229 | } |
pmic | 0:211f27847e85 | 1230 | } |
pmic | 0:211f27847e85 | 1231 | return count; |
pmic | 0:211f27847e85 | 1232 | */ |
pmic | 0:211f27847e85 | 1233 | int i; |
pmic | 0:211f27847e85 | 1234 | char temp_dest[count]; |
pmic | 0:211f27847e85 | 1235 | char temp[1] = {subAddress}; |
pmic | 0:211f27847e85 | 1236 | i2c.write(address, temp, 1); |
pmic | 0:211f27847e85 | 1237 | i2c.read(address, temp_dest, count); |
pmic | 0:211f27847e85 | 1238 | |
pmic | 0:211f27847e85 | 1239 | //i2c doesn't take uint8_ts, but rather chars so do this nasty af conversion |
pmic | 0:211f27847e85 | 1240 | for (i=0; i < count; i++) { |
pmic | 0:211f27847e85 | 1241 | dest[i] = temp_dest[i]; |
pmic | 0:211f27847e85 | 1242 | } |
pmic | 0:211f27847e85 | 1243 | return count; |
pmic | 0:211f27847e85 | 1244 | } |
pmic | 0:211f27847e85 | 1245 | |
pmic | 0:211f27847e85 | 1246 |