AHRS

Dependencies:   Eigen

Dependents:   IndNav_QK3_T265

Committer:
pmic
Date:
Wed Sep 04 09:05:12 2019 +0000
Revision:
12:1070a10a4624
Parent:
7:bfde7bd5fe31
Child:
13:3a41ef85fe7e
Add measured correction gain 1.17 to void readGyro.

Who changed what in which revision?

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