IMU LSM9DS1 Library

Dependencies:   PinDetect mbed

Dependents:   Latch9DOF_LSM9DS1

Fork of LSM9DS1_Library by Jason Mar

Committer:
afmiee
Date:
Fri Jul 15 22:37:51 2016 +0000
Revision:
2:fbee92c6190d
Parent:
1:87d535bf8c53
Child:
3:585984c4a4b1
Made some minor changes to library to compile

Who changed what in which revision?

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