Curtis Cooper
/
LSM9DS1_Library_cal_new
my fork
Embed:
(wiki syntax)
Show/hide line numbers
LSM9DS1.cpp
00001 /****************************************************************************** 00002 SFE_LSM9DS1.cpp 00003 SFE_LSM9DS1 Library Source File 00004 Jim Lindblom @ SparkFun Electronics 00005 Original Creation Date: February 27, 2015 00006 https://github.com/sparkfun/LSM9DS1_Breakout 00007 00008 This file implements all functions of the LSM9DS1 class. Functions here range 00009 from higher level stuff, like reading/writing LSM9DS1 registers to low-level, 00010 hardware reads and writes. Both SPI and I2C handler functions can be found 00011 towards the bottom of this file. 00012 00013 Development environment specifics: 00014 IDE: Arduino 1.6 00015 Hardware Platform: Arduino Uno 00016 LSM9DS1 Breakout Version: 1.0 00017 00018 This code is beerware; if you see me (or any other SparkFun employee) at the 00019 local, and you've found our code helpful, please buy us a round! 00020 00021 Distributed as-is; no warranty is given. 00022 ******************************************************************************/ 00023 00024 #include "LSM9DS1.h" 00025 #include "LSM9DS1_Registers.h" 00026 #include "LSM9DS1_Types.h" 00027 //#include <Wire.h> // Wire library is used for I2C 00028 //#include <SPI.h> // SPI library is used for...SPI. 00029 00030 //#if defined(ARDUINO) && ARDUINO >= 100 00031 // #include "Arduino.h" 00032 //#else 00033 // #include "WProgram.h" 00034 //#endif 00035 00036 #define LSM9DS1_COMMUNICATION_TIMEOUT 1000 00037 DigitalOut startCal(LED4); 00038 DigitalOut finishedCal(LED3); 00039 00040 float magSensitivity[4] = {0.00014, 0.00029, 0.00043, 0.00058}; 00041 extern Serial pc; 00042 00043 LSM9DS1::LSM9DS1(PinName sda, PinName scl, uint8_t xgAddr, uint8_t mAddr) 00044 :i2c(sda, scl) 00045 { 00046 init(IMU_MODE_I2C, xgAddr, mAddr); // dont know about 0xD6 or 0x3B 00047 } 00048 /* 00049 LSM9DS1::LSM9DS1() 00050 { 00051 init(IMU_MODE_I2C, LSM9DS1_AG_ADDR(1), LSM9DS1_M_ADDR(1)); 00052 } 00053 00054 LSM9DS1::LSM9DS1(interface_mode interface, uint8_t xgAddr, uint8_t mAddr) 00055 { 00056 init(interface, xgAddr, mAddr); 00057 } 00058 */ 00059 00060 void LSM9DS1::init(interface_mode interface, uint8_t xgAddr, uint8_t mAddr) 00061 { 00062 settings.device.commInterface = interface; 00063 settings.device.agAddress = xgAddr; 00064 settings.device.mAddress = mAddr; 00065 00066 settings.gyro.enabled = true; 00067 settings.gyro.enableX = true; 00068 settings.gyro.enableY = true; 00069 settings.gyro.enableZ = true; 00070 // gyro scale can be 245, 500, or 2000 00071 settings.gyro.scale = 245; 00072 // gyro sample rate: value between 1-6 00073 // 1 = 14.9 4 = 238 00074 // 2 = 59.5 5 = 476 00075 // 3 = 119 6 = 952 00076 settings.gyro.sampleRate = 6; 00077 // gyro cutoff frequency: value between 0-3 00078 // Actual value of cutoff frequency depends 00079 // on sample rate. 00080 settings.gyro.bandwidth = 0; 00081 settings.gyro.lowPowerEnable = false; 00082 settings.gyro.HPFEnable = false; 00083 // Gyro HPF cutoff frequency: value between 0-9 00084 // Actual value depends on sample rate. Only applies 00085 // if gyroHPFEnable is true. 00086 settings.gyro.HPFCutoff = 0; 00087 settings.gyro.flipX = false; 00088 settings.gyro.flipY = false; 00089 settings.gyro.flipZ = false; 00090 settings.gyro.orientation = 0; 00091 settings.gyro.latchInterrupt = true; 00092 00093 settings.accel.enabled = true; 00094 settings.accel.enableX = true; 00095 settings.accel.enableY = true; 00096 settings.accel.enableZ = true; 00097 // accel scale can be 2, 4, 8, or 16 00098 settings.accel.scale = 2; 00099 // accel sample rate can be 1-6 00100 // 1 = 10 Hz 4 = 238 Hz 00101 // 2 = 50 Hz 5 = 476 Hz 00102 // 3 = 119 Hz 6 = 952 Hz 00103 settings.accel.sampleRate = 6; 00104 // Accel cutoff freqeuncy can be any value between -1 - 3. 00105 // -1 = bandwidth determined by sample rate 00106 // 0 = 408 Hz 2 = 105 Hz 00107 // 1 = 211 Hz 3 = 50 Hz 00108 settings.accel.bandwidth = -1; 00109 settings.accel.highResEnable = false; 00110 // accelHighResBandwidth can be any value between 0-3 00111 // LP cutoff is set to a factor of sample rate 00112 // 0 = ODR/50 2 = ODR/9 00113 // 1 = ODR/100 3 = ODR/400 00114 settings.accel.highResBandwidth = 0; 00115 00116 settings.mag.enabled = true; 00117 // mag scale can be 4, 8, 12, or 16 00118 settings.mag.scale = 4; 00119 // mag data rate can be 0-7 00120 // 0 = 0.625 Hz 4 = 10 Hz 00121 // 1 = 1.25 Hz 5 = 20 Hz 00122 // 2 = 2.5 Hz 6 = 40 Hz 00123 // 3 = 5 Hz 7 = 80 Hz 00124 settings.mag.sampleRate = 7; 00125 settings.mag.tempCompensationEnable = false; 00126 // magPerformance can be any value between 0-3 00127 // 0 = Low power mode 2 = high performance 00128 // 1 = medium performance 3 = ultra-high performance 00129 settings.mag.XYPerformance = 3; 00130 settings.mag.ZPerformance = 3; 00131 settings.mag.lowPowerEnable = false; 00132 // magOperatingMode can be 0-2 00133 // 0 = continuous conversion 00134 // 1 = single-conversion 00135 // 2 = power down 00136 settings.mag.operatingMode = 0; 00137 00138 settings.temp.enabled = true; 00139 for (int i=0; i<3; i++) { 00140 gBias[i] = 0; 00141 aBias[i] = 0; 00142 mBias[i] = 0; 00143 gBiasRaw[i] = 0; 00144 aBiasRaw[i] = 0; 00145 mBiasRaw[i] = 0; 00146 } 00147 _autoCalc = false; 00148 } 00149 00150 00151 uint16_t LSM9DS1::begin() 00152 { 00153 //! Todo: don't use _xgAddress or _mAddress, duplicating memory 00154 _xgAddress = settings.device.agAddress; 00155 _mAddress = settings.device.mAddress; 00156 00157 constrainScales(); 00158 // Once we have the scale values, we can calculate the resolution 00159 // of each sensor. That's what these functions are for. One for each sensor 00160 calcgRes(); // Calculate DPS / ADC tick, stored in gRes variable 00161 calcmRes(); // Calculate Gs / ADC tick, stored in mRes variable 00162 calcaRes(); // Calculate g / ADC tick, stored in aRes variable 00163 00164 // Now, initialize our hardware interface. 00165 if (settings.device.commInterface == IMU_MODE_I2C) // If we're using I2C 00166 initI2C(); // Initialize I2C 00167 else if (settings.device.commInterface == IMU_MODE_SPI) // else, if we're using SPI 00168 initSPI(); // Initialize SPI 00169 00170 // To verify communication, we can read from the WHO_AM_I register of 00171 // each device. Store those in a variable so we can return them. 00172 uint8_t mTest = mReadByte(WHO_AM_I_M); // Read the gyro WHO_AM_I 00173 uint8_t xgTest = xgReadByte(WHO_AM_I_XG); // Read the accel/mag WHO_AM_I 00174 pc.printf("%x, %x, %x, %x\n\r", mTest, xgTest, _xgAddress, _mAddress); 00175 uint16_t whoAmICombined = (xgTest << 8) | mTest; 00176 00177 if (whoAmICombined != ((WHO_AM_I_AG_RSP << 8) | WHO_AM_I_M_RSP)) 00178 return 0; 00179 00180 // Gyro initialization stuff: 00181 initGyro(); // This will "turn on" the gyro. Setting up interrupts, etc. 00182 00183 // Accelerometer initialization stuff: 00184 initAccel(); // "Turn on" all axes of the accel. Set up interrupts, etc. 00185 00186 // Magnetometer initialization stuff: 00187 initMag(); // "Turn on" all axes of the mag. Set up interrupts, etc. 00188 00189 // Once everything is initialized, return the WHO_AM_I registers we read: 00190 return whoAmICombined; 00191 } 00192 00193 void LSM9DS1::initGyro() 00194 { 00195 uint8_t tempRegValue = 0; 00196 00197 // CTRL_REG1_G (Default value: 0x00) 00198 // [ODR_G2][ODR_G1][ODR_G0][FS_G1][FS_G0][0][BW_G1][BW_G0] 00199 // ODR_G[2:0] - Output data rate selection 00200 // FS_G[1:0] - Gyroscope full-scale selection 00201 // BW_G[1:0] - Gyroscope bandwidth selection 00202 00203 // To disable gyro, set sample rate bits to 0. We'll only set sample 00204 // rate if the gyro is enabled. 00205 if (settings.gyro.enabled) { 00206 tempRegValue = (settings.gyro.sampleRate & 0x07) << 5; 00207 } 00208 switch (settings.gyro.scale) { 00209 case 500: 00210 tempRegValue |= (0x1 << 3); 00211 break; 00212 case 2000: 00213 tempRegValue |= (0x3 << 3); 00214 break; 00215 // Otherwise we'll set it to 245 dps (0x0 << 4) 00216 } 00217 tempRegValue |= (settings.gyro.bandwidth & 0x3); 00218 xgWriteByte(CTRL_REG1_G, tempRegValue); 00219 00220 // CTRL_REG2_G (Default value: 0x00) 00221 // [0][0][0][0][INT_SEL1][INT_SEL0][OUT_SEL1][OUT_SEL0] 00222 // INT_SEL[1:0] - INT selection configuration 00223 // OUT_SEL[1:0] - Out selection configuration 00224 xgWriteByte(CTRL_REG2_G, 0x00); 00225 00226 // CTRL_REG3_G (Default value: 0x00) 00227 // [LP_mode][HP_EN][0][0][HPCF3_G][HPCF2_G][HPCF1_G][HPCF0_G] 00228 // LP_mode - Low-power mode enable (0: disabled, 1: enabled) 00229 // HP_EN - HPF enable (0:disabled, 1: enabled) 00230 // HPCF_G[3:0] - HPF cutoff frequency 00231 tempRegValue = settings.gyro.lowPowerEnable ? (1<<7) : 0; 00232 if (settings.gyro.HPFEnable) { 00233 tempRegValue |= (1<<6) | (settings.gyro.HPFCutoff & 0x0F); 00234 } 00235 xgWriteByte(CTRL_REG3_G, tempRegValue); 00236 00237 // CTRL_REG4 (Default value: 0x38) 00238 // [0][0][Zen_G][Yen_G][Xen_G][0][LIR_XL1][4D_XL1] 00239 // Zen_G - Z-axis output enable (0:disable, 1:enable) 00240 // Yen_G - Y-axis output enable (0:disable, 1:enable) 00241 // Xen_G - X-axis output enable (0:disable, 1:enable) 00242 // LIR_XL1 - Latched interrupt (0:not latched, 1:latched) 00243 // 4D_XL1 - 4D option on interrupt (0:6D used, 1:4D used) 00244 tempRegValue = 0; 00245 if (settings.gyro.enableZ) tempRegValue |= (1<<5); 00246 if (settings.gyro.enableY) tempRegValue |= (1<<4); 00247 if (settings.gyro.enableX) tempRegValue |= (1<<3); 00248 if (settings.gyro.latchInterrupt) tempRegValue |= (1<<1); 00249 xgWriteByte(CTRL_REG4, tempRegValue); 00250 00251 // ORIENT_CFG_G (Default value: 0x00) 00252 // [0][0][SignX_G][SignY_G][SignZ_G][Orient_2][Orient_1][Orient_0] 00253 // SignX_G - Pitch axis (X) angular rate sign (0: positive, 1: negative) 00254 // Orient [2:0] - Directional user orientation selection 00255 tempRegValue = 0; 00256 if (settings.gyro.flipX) tempRegValue |= (1<<5); 00257 if (settings.gyro.flipY) tempRegValue |= (1<<4); 00258 if (settings.gyro.flipZ) tempRegValue |= (1<<3); 00259 xgWriteByte(ORIENT_CFG_G, tempRegValue); 00260 } 00261 00262 void LSM9DS1::initAccel() 00263 { 00264 uint8_t tempRegValue = 0; 00265 00266 // CTRL_REG5_XL (0x1F) (Default value: 0x38) 00267 // [DEC_1][DEC_0][Zen_XL][Yen_XL][Zen_XL][0][0][0] 00268 // DEC[0:1] - Decimation of accel data on OUT REG and FIFO. 00269 // 00: None, 01: 2 samples, 10: 4 samples 11: 8 samples 00270 // Zen_XL - Z-axis output enabled 00271 // Yen_XL - Y-axis output enabled 00272 // Xen_XL - X-axis output enabled 00273 if (settings.accel.enableZ) tempRegValue |= (1<<5); 00274 if (settings.accel.enableY) tempRegValue |= (1<<4); 00275 if (settings.accel.enableX) tempRegValue |= (1<<3); 00276 00277 xgWriteByte(CTRL_REG5_XL, tempRegValue); 00278 00279 // CTRL_REG6_XL (0x20) (Default value: 0x00) 00280 // [ODR_XL2][ODR_XL1][ODR_XL0][FS1_XL][FS0_XL][BW_SCAL_ODR][BW_XL1][BW_XL0] 00281 // ODR_XL[2:0] - Output data rate & power mode selection 00282 // FS_XL[1:0] - Full-scale selection 00283 // BW_SCAL_ODR - Bandwidth selection 00284 // BW_XL[1:0] - Anti-aliasing filter bandwidth selection 00285 tempRegValue = 0; 00286 // To disable the accel, set the sampleRate bits to 0. 00287 if (settings.accel.enabled) { 00288 tempRegValue |= (settings.accel.sampleRate & 0x07) << 5; 00289 } 00290 switch (settings.accel.scale) { 00291 case 4: 00292 tempRegValue |= (0x2 << 3); 00293 break; 00294 case 8: 00295 tempRegValue |= (0x3 << 3); 00296 break; 00297 case 16: 00298 tempRegValue |= (0x1 << 3); 00299 break; 00300 // Otherwise it'll be set to 2g (0x0 << 3) 00301 } 00302 if (settings.accel.bandwidth >= 0) { 00303 tempRegValue |= (1<<2); // Set BW_SCAL_ODR 00304 tempRegValue |= (settings.accel.bandwidth & 0x03); 00305 } 00306 xgWriteByte(CTRL_REG6_XL, tempRegValue); 00307 00308 // CTRL_REG7_XL (0x21) (Default value: 0x00) 00309 // [HR][DCF1][DCF0][0][0][FDS][0][HPIS1] 00310 // HR - High resolution mode (0: disable, 1: enable) 00311 // DCF[1:0] - Digital filter cutoff frequency 00312 // FDS - Filtered data selection 00313 // HPIS1 - HPF enabled for interrupt function 00314 tempRegValue = 0; 00315 if (settings.accel.highResEnable) { 00316 tempRegValue |= (1<<7); // Set HR bit 00317 tempRegValue |= (settings.accel.highResBandwidth & 0x3) << 5; 00318 } 00319 xgWriteByte(CTRL_REG7_XL, tempRegValue); 00320 } 00321 00322 // This is a function that uses the FIFO to accumulate sample of accelerometer and gyro data, average 00323 // them, scales them to gs and deg/s, respectively, and then passes the biases to the main sketch 00324 // for subtraction from all subsequent data. There are no gyro and accelerometer bias registers to store 00325 // the data as there are in the ADXL345, a precursor to the LSM9DS0, or the MPU-9150, so we have to 00326 // subtract the biases ourselves. This results in a more accurate measurement in general and can 00327 // remove errors due to imprecise or varying initial placement. Calibration of sensor data in this manner 00328 // is good practice. 00329 void LSM9DS1::calibrate(bool autoCalc) 00330 { 00331 uint8_t data[6] = {0, 0, 0, 0, 0, 0}; 00332 uint8_t samples = 0; 00333 int ii; 00334 int32_t aBiasRawTemp[3] = {0, 0, 0}; 00335 int32_t gBiasRawTemp[3] = {0, 0, 0}; 00336 pc.printf("\n\rPlace IMU on level surface and do not move it for gyro and accel calibration.\n\r"); 00337 wait(1); 00338 // Turn on FIFO and set threshold to 32 samples 00339 enableFIFO(true); 00340 setFIFO(FIFO_THS, 0x1F); 00341 while (samples < 0x1F) { 00342 samples = (xgReadByte(FIFO_SRC) & 0x3F); // Read number of stored samples 00343 } 00344 for(ii = 0; ii < samples ; ii++) { 00345 // Read the gyro data stored in the FIFO 00346 readGyro(); 00347 gBiasRawTemp[0] += gx; 00348 gBiasRawTemp[1] += gy; 00349 gBiasRawTemp[2] += gz; 00350 readAccel(); 00351 aBiasRawTemp[0] += ax; 00352 aBiasRawTemp[1] += ay; 00353 aBiasRawTemp[2] += az - (int16_t)(1./aRes); // Assumes sensor facing up! 00354 } 00355 for (ii = 0; ii < 3; ii++) { 00356 gBiasRaw[ii] = gBiasRawTemp[ii] / samples; 00357 gBias[ii] = calcGyro(gBiasRaw[ii]); 00358 aBiasRaw[ii] = aBiasRawTemp[ii] / samples; 00359 aBias[ii] = calcAccel(aBiasRaw[ii]); 00360 } 00361 00362 enableFIFO(false); 00363 setFIFO(FIFO_OFF, 0x00); 00364 00365 if (autoCalc) _autoCalc = true; 00366 } 00367 00368 void LSM9DS1::calibrateMag(bool loadIn) 00369 { 00370 int i, j; 00371 int16_t magMin[3] = {0, 0, 0}; 00372 int16_t magMax[3] = {0, 0, 0}; // The road warrior 00373 startCal = 1; 00374 //pc.printf("\n\n\r Rotate IMU device at least 360 in horizontal plane for magnetometer calibration\n\r"); 00375 wait(0.5); 00376 for (i=0; i<1000; i++) { 00377 while (!magAvailable(ALL_AXIS)); 00378 readMag(); 00379 int16_t magTemp[3] = {0, 0, 0}; 00380 magTemp[0] = mx; 00381 magTemp[1] = my; 00382 magTemp[2] = mz; 00383 for (j = 0; j < 3; j++) { 00384 if (magTemp[j] > magMax[j]) magMax[j] = magTemp[j]; 00385 if (magTemp[j] < magMin[j]) magMin[j] = magTemp[j]; 00386 } 00387 } 00388 for (j = 0; j < 3; j++) { 00389 mBiasRaw[j] = (magMax[j] + magMin[j]) / 2; 00390 mBias[j] = calcMag(mBiasRaw[j]); 00391 pc.printf("%f ",mBias[j]); 00392 if (loadIn) 00393 magOffset(j, mBiasRaw[j]); 00394 } 00395 //pc.printf("\n\rMAG calibration done\n\r"); 00396 finishedCal = 1; 00397 startCal = 0; 00398 wait(.5); 00399 finishedCal = 0; 00400 } 00401 void LSM9DS1::magOffset(uint8_t axis, int16_t offset) 00402 { 00403 if (axis > 2) 00404 return; 00405 uint8_t msb, lsb; 00406 msb = (offset & 0xFF00) >> 8; 00407 lsb = offset & 0x00FF; 00408 mWriteByte(OFFSET_X_REG_L_M + (2 * axis), lsb); 00409 mWriteByte(OFFSET_X_REG_H_M + (2 * axis), msb); 00410 } 00411 00412 void LSM9DS1::initMag() 00413 { 00414 uint8_t tempRegValue = 0; 00415 00416 // CTRL_REG1_M (Default value: 0x10) 00417 // [TEMP_COMP][OM1][OM0][DO2][DO1][DO0][0][ST] 00418 // TEMP_COMP - Temperature compensation 00419 // OM[1:0] - X & Y axes op mode selection 00420 // 00:low-power, 01:medium performance 00421 // 10: high performance, 11:ultra-high performance 00422 // DO[2:0] - Output data rate selection 00423 // ST - Self-test enable 00424 if (settings.mag.tempCompensationEnable) tempRegValue |= (1<<7); 00425 tempRegValue |= (settings.mag.XYPerformance & 0x3) << 5; 00426 tempRegValue |= (settings.mag.sampleRate & 0x7) << 2; 00427 mWriteByte(CTRL_REG1_M, tempRegValue); 00428 00429 // CTRL_REG2_M (Default value 0x00) 00430 // [0][FS1][FS0][0][REBOOT][SOFT_RST][0][0] 00431 // FS[1:0] - Full-scale configuration 00432 // REBOOT - Reboot memory content (0:normal, 1:reboot) 00433 // SOFT_RST - Reset config and user registers (0:default, 1:reset) 00434 tempRegValue = 0; 00435 switch (settings.mag.scale) { 00436 case 8: 00437 tempRegValue |= (0x1 << 5); 00438 break; 00439 case 12: 00440 tempRegValue |= (0x2 << 5); 00441 break; 00442 case 16: 00443 tempRegValue |= (0x3 << 5); 00444 break; 00445 // Otherwise we'll default to 4 gauss (00) 00446 } 00447 mWriteByte(CTRL_REG2_M, tempRegValue); // +/-4Gauss 00448 00449 // CTRL_REG3_M (Default value: 0x03) 00450 // [I2C_DISABLE][0][LP][0][0][SIM][MD1][MD0] 00451 // I2C_DISABLE - Disable I2C interace (0:enable, 1:disable) 00452 // LP - Low-power mode cofiguration (1:enable) 00453 // SIM - SPI mode selection (0:write-only, 1:read/write enable) 00454 // MD[1:0] - Operating mode 00455 // 00:continuous conversion, 01:single-conversion, 00456 // 10,11: Power-down 00457 tempRegValue = 0; 00458 if (settings.mag.lowPowerEnable) tempRegValue |= (1<<5); 00459 tempRegValue |= (settings.mag.operatingMode & 0x3); 00460 mWriteByte(CTRL_REG3_M, tempRegValue); // Continuous conversion mode 00461 00462 // CTRL_REG4_M (Default value: 0x00) 00463 // [0][0][0][0][OMZ1][OMZ0][BLE][0] 00464 // OMZ[1:0] - Z-axis operative mode selection 00465 // 00:low-power mode, 01:medium performance 00466 // 10:high performance, 10:ultra-high performance 00467 // BLE - Big/little endian data 00468 tempRegValue = 0; 00469 tempRegValue = (settings.mag.ZPerformance & 0x3) << 2; 00470 mWriteByte(CTRL_REG4_M, tempRegValue); 00471 00472 // CTRL_REG5_M (Default value: 0x00) 00473 // [0][BDU][0][0][0][0][0][0] 00474 // BDU - Block data update for magnetic data 00475 // 0:continuous, 1:not updated until MSB/LSB are read 00476 tempRegValue = 0; 00477 mWriteByte(CTRL_REG5_M, tempRegValue); 00478 } 00479 00480 uint8_t LSM9DS1::accelAvailable() 00481 { 00482 uint8_t status = xgReadByte(STATUS_REG_1); 00483 00484 return (status & (1<<0)); 00485 } 00486 00487 uint8_t LSM9DS1::gyroAvailable() 00488 { 00489 uint8_t status = xgReadByte(STATUS_REG_1); 00490 00491 return ((status & (1<<1)) >> 1); 00492 } 00493 00494 uint8_t LSM9DS1::tempAvailable() 00495 { 00496 uint8_t status = xgReadByte(STATUS_REG_1); 00497 00498 return ((status & (1<<2)) >> 2); 00499 } 00500 00501 uint8_t LSM9DS1::magAvailable(lsm9ds1_axis axis) 00502 { 00503 uint8_t status; 00504 status = mReadByte(STATUS_REG_M); 00505 00506 return ((status & (1<<axis)) >> axis); 00507 } 00508 00509 void LSM9DS1::readAccel() 00510 { 00511 uint8_t temp[6]; // We'll read six bytes from the accelerometer into temp 00512 xgReadBytes(OUT_X_L_XL, temp, 6); // Read 6 bytes, beginning at OUT_X_L_XL 00513 ax = (temp[1] << 8) | temp[0]; // Store x-axis values into ax 00514 ay = (temp[3] << 8) | temp[2]; // Store y-axis values into ay 00515 az = (temp[5] << 8) | temp[4]; // Store z-axis values into az 00516 if (_autoCalc) { 00517 ax -= aBiasRaw[X_AXIS]; 00518 ay -= aBiasRaw[Y_AXIS]; 00519 az -= aBiasRaw[Z_AXIS]; 00520 } 00521 } 00522 00523 int16_t LSM9DS1::readAccel(lsm9ds1_axis axis) 00524 { 00525 uint8_t temp[2]; 00526 int16_t value; 00527 xgReadBytes(OUT_X_L_XL + (2 * axis), temp, 2); 00528 value = (temp[1] << 8) | temp[0]; 00529 00530 if (_autoCalc) 00531 value -= aBiasRaw[axis]; 00532 00533 return value; 00534 } 00535 00536 void LSM9DS1::readMag() 00537 { 00538 uint8_t temp[6]; // We'll read six bytes from the mag into temp 00539 mReadBytes(OUT_X_L_M, temp, 6); // Read 6 bytes, beginning at OUT_X_L_M 00540 mx = (temp[1] << 8) | temp[0]; // Store x-axis values into mx 00541 my = (temp[3] << 8) | temp[2]; // Store y-axis values into my 00542 mz = (temp[5] << 8) | temp[4]; // Store z-axis values into mz 00543 mx = mx - mBiasRaw[0]; 00544 my = my - mBiasRaw[1]; 00545 mz = mz - mBiasRaw[2]; 00546 } 00547 00548 int16_t LSM9DS1::readMag(lsm9ds1_axis axis) 00549 { 00550 uint8_t temp[2]; 00551 mReadBytes(OUT_X_L_M + (2 * axis), temp, 2); 00552 return (temp[1] << 8) | temp[0]; 00553 } 00554 00555 void LSM9DS1::readTemp() 00556 { 00557 uint8_t temp[2]; // We'll read two bytes from the temperature sensor into temp 00558 xgReadBytes(OUT_TEMP_L, temp, 2); // Read 2 bytes, beginning at OUT_TEMP_L 00559 temperature = (int16_t)((temp[1] << 8) | temp[0]); 00560 } 00561 00562 void LSM9DS1::readGyro() 00563 { 00564 uint8_t temp[6]; // We'll read six bytes from the gyro into temp 00565 xgReadBytes(OUT_X_L_G, temp, 6); // Read 6 bytes, beginning at OUT_X_L_G 00566 gx = (temp[1] << 8) | temp[0]; // Store x-axis values into gx 00567 gy = (temp[3] << 8) | temp[2]; // Store y-axis values into gy 00568 gz = (temp[5] << 8) | temp[4]; // Store z-axis values into gz 00569 if (_autoCalc) { 00570 gx -= gBiasRaw[X_AXIS]; 00571 gy -= gBiasRaw[Y_AXIS]; 00572 gz -= gBiasRaw[Z_AXIS]; 00573 } 00574 } 00575 00576 int16_t LSM9DS1::readGyro(lsm9ds1_axis axis) 00577 { 00578 uint8_t temp[2]; 00579 int16_t value; 00580 00581 xgReadBytes(OUT_X_L_G + (2 * axis), temp, 2); 00582 00583 value = (temp[1] << 8) | temp[0]; 00584 00585 if (_autoCalc) 00586 value -= gBiasRaw[axis]; 00587 00588 return value; 00589 } 00590 00591 float LSM9DS1::calcGyro(int16_t gyro) 00592 { 00593 // Return the gyro raw reading times our pre-calculated DPS / (ADC tick): 00594 return gRes * gyro; 00595 } 00596 00597 float LSM9DS1::calcAccel(int16_t accel) 00598 { 00599 // Return the accel raw reading times our pre-calculated g's / (ADC tick): 00600 return aRes * accel; 00601 } 00602 00603 float LSM9DS1::calcMag(int16_t mag) 00604 { 00605 // Return the mag raw reading times our pre-calculated Gs / (ADC tick): 00606 return mRes * mag; 00607 } 00608 00609 void LSM9DS1::setGyroScale(uint16_t gScl) 00610 { 00611 // Read current value of CTRL_REG1_G: 00612 uint8_t ctrl1RegValue = xgReadByte(CTRL_REG1_G); 00613 // Mask out scale bits (3 & 4): 00614 ctrl1RegValue &= 0xE7; 00615 switch (gScl) { 00616 case 500: 00617 ctrl1RegValue |= (0x1 << 3); 00618 settings.gyro.scale = 500; 00619 break; 00620 case 2000: 00621 ctrl1RegValue |= (0x3 << 3); 00622 settings.gyro.scale = 2000; 00623 break; 00624 default: // Otherwise we'll set it to 245 dps (0x0 << 4) 00625 settings.gyro.scale = 245; 00626 break; 00627 } 00628 xgWriteByte(CTRL_REG1_G, ctrl1RegValue); 00629 00630 calcgRes(); 00631 } 00632 00633 void LSM9DS1::setAccelScale(uint8_t aScl) 00634 { 00635 // We need to preserve the other bytes in CTRL_REG6_XL. So, first read it: 00636 uint8_t tempRegValue = xgReadByte(CTRL_REG6_XL); 00637 // Mask out accel scale bits: 00638 tempRegValue &= 0xE7; 00639 00640 switch (aScl) { 00641 case 4: 00642 tempRegValue |= (0x2 << 3); 00643 settings.accel.scale = 4; 00644 break; 00645 case 8: 00646 tempRegValue |= (0x3 << 3); 00647 settings.accel.scale = 8; 00648 break; 00649 case 16: 00650 tempRegValue |= (0x1 << 3); 00651 settings.accel.scale = 16; 00652 break; 00653 default: // Otherwise it'll be set to 2g (0x0 << 3) 00654 settings.accel.scale = 2; 00655 break; 00656 } 00657 xgWriteByte(CTRL_REG6_XL, tempRegValue); 00658 00659 // Then calculate a new aRes, which relies on aScale being set correctly: 00660 calcaRes(); 00661 } 00662 00663 void LSM9DS1::setMagScale(uint8_t mScl) 00664 { 00665 // We need to preserve the other bytes in CTRL_REG6_XM. So, first read it: 00666 uint8_t temp = mReadByte(CTRL_REG2_M); 00667 // Then mask out the mag scale bits: 00668 temp &= 0xFF^(0x3 << 5); 00669 00670 switch (mScl) { 00671 case 8: 00672 temp |= (0x1 << 5); 00673 settings.mag.scale = 8; 00674 break; 00675 case 12: 00676 temp |= (0x2 << 5); 00677 settings.mag.scale = 12; 00678 break; 00679 case 16: 00680 temp |= (0x3 << 5); 00681 settings.mag.scale = 16; 00682 break; 00683 default: // Otherwise we'll default to 4 gauss (00) 00684 settings.mag.scale = 4; 00685 break; 00686 } 00687 00688 // And write the new register value back into CTRL_REG6_XM: 00689 mWriteByte(CTRL_REG2_M, temp); 00690 00691 // We've updated the sensor, but we also need to update our class variables 00692 // First update mScale: 00693 //mScale = mScl; 00694 // Then calculate a new mRes, which relies on mScale being set correctly: 00695 calcmRes(); 00696 } 00697 00698 void LSM9DS1::setGyroODR(uint8_t gRate) 00699 { 00700 // Only do this if gRate is not 0 (which would disable the gyro) 00701 if ((gRate & 0x07) != 0) { 00702 // We need to preserve the other bytes in CTRL_REG1_G. So, first read it: 00703 uint8_t temp = xgReadByte(CTRL_REG1_G); 00704 // Then mask out the gyro ODR bits: 00705 temp &= 0xFF^(0x7 << 5); 00706 temp |= (gRate & 0x07) << 5; 00707 // Update our settings struct 00708 settings.gyro.sampleRate = gRate & 0x07; 00709 // And write the new register value back into CTRL_REG1_G: 00710 xgWriteByte(CTRL_REG1_G, temp); 00711 } 00712 } 00713 00714 void LSM9DS1::setAccelODR(uint8_t aRate) 00715 { 00716 // Only do this if aRate is not 0 (which would disable the accel) 00717 if ((aRate & 0x07) != 0) { 00718 // We need to preserve the other bytes in CTRL_REG1_XM. So, first read it: 00719 uint8_t temp = xgReadByte(CTRL_REG6_XL); 00720 // Then mask out the accel ODR bits: 00721 temp &= 0x1F; 00722 // Then shift in our new ODR bits: 00723 temp |= ((aRate & 0x07) << 5); 00724 settings.accel.sampleRate = aRate & 0x07; 00725 // And write the new register value back into CTRL_REG1_XM: 00726 xgWriteByte(CTRL_REG6_XL, temp); 00727 } 00728 } 00729 00730 void LSM9DS1::setMagODR(uint8_t mRate) 00731 { 00732 // We need to preserve the other bytes in CTRL_REG5_XM. So, first read it: 00733 uint8_t temp = mReadByte(CTRL_REG1_M); 00734 // Then mask out the mag ODR bits: 00735 temp &= 0xFF^(0x7 << 2); 00736 // Then shift in our new ODR bits: 00737 temp |= ((mRate & 0x07) << 2); 00738 settings.mag.sampleRate = mRate & 0x07; 00739 // And write the new register value back into CTRL_REG5_XM: 00740 mWriteByte(CTRL_REG1_M, temp); 00741 } 00742 00743 void LSM9DS1::calcgRes() 00744 { 00745 gRes = ((float) settings.gyro.scale) / 32768.0; 00746 } 00747 00748 void LSM9DS1::calcaRes() 00749 { 00750 aRes = ((float) settings.accel.scale) / 32768.0; 00751 } 00752 00753 void LSM9DS1::calcmRes() 00754 { 00755 //mRes = ((float) settings.mag.scale) / 32768.0; 00756 switch (settings.mag.scale) { 00757 case 4: 00758 mRes = magSensitivity[0]; 00759 break; 00760 case 8: 00761 mRes = magSensitivity[1]; 00762 break; 00763 case 12: 00764 mRes = magSensitivity[2]; 00765 break; 00766 case 16: 00767 mRes = magSensitivity[3]; 00768 break; 00769 } 00770 00771 } 00772 00773 void LSM9DS1::configInt(interrupt_select interrupt, uint8_t generator, 00774 h_lactive activeLow, pp_od pushPull) 00775 { 00776 // Write to INT1_CTRL or INT2_CTRL. [interupt] should already be one of 00777 // those two values. 00778 // [generator] should be an OR'd list of values from the interrupt_generators enum 00779 xgWriteByte(interrupt, generator); 00780 00781 // Configure CTRL_REG8 00782 uint8_t temp; 00783 temp = xgReadByte(CTRL_REG8); 00784 00785 if (activeLow) temp |= (1<<5); 00786 else temp &= ~(1<<5); 00787 00788 if (pushPull) temp &= ~(1<<4); 00789 else temp |= (1<<4); 00790 00791 xgWriteByte(CTRL_REG8, temp); 00792 } 00793 00794 void LSM9DS1::configInactivity(uint8_t duration, uint8_t threshold, bool sleepOn) 00795 { 00796 uint8_t temp = 0; 00797 00798 temp = threshold & 0x7F; 00799 if (sleepOn) temp |= (1<<7); 00800 xgWriteByte(ACT_THS, temp); 00801 00802 xgWriteByte(ACT_DUR, duration); 00803 } 00804 00805 uint8_t LSM9DS1::getInactivity() 00806 { 00807 uint8_t temp = xgReadByte(STATUS_REG_0); 00808 temp &= (0x10); 00809 return temp; 00810 } 00811 00812 void LSM9DS1::configAccelInt(uint8_t generator, bool andInterrupts) 00813 { 00814 // Use variables from accel_interrupt_generator, OR'd together to create 00815 // the [generator]value. 00816 uint8_t temp = generator; 00817 if (andInterrupts) temp |= 0x80; 00818 xgWriteByte(INT_GEN_CFG_XL, temp); 00819 } 00820 00821 void LSM9DS1::configAccelThs(uint8_t threshold, lsm9ds1_axis axis, uint8_t duration, bool wait) 00822 { 00823 // Write threshold value to INT_GEN_THS_?_XL. 00824 // axis will be 0, 1, or 2 (x, y, z respectively) 00825 xgWriteByte(INT_GEN_THS_X_XL + axis, threshold); 00826 00827 // Write duration and wait to INT_GEN_DUR_XL 00828 uint8_t temp; 00829 temp = (duration & 0x7F); 00830 if (wait) temp |= 0x80; 00831 xgWriteByte(INT_GEN_DUR_XL, temp); 00832 } 00833 00834 uint8_t LSM9DS1::getAccelIntSrc() 00835 { 00836 uint8_t intSrc = xgReadByte(INT_GEN_SRC_XL); 00837 00838 // Check if the IA_XL (interrupt active) bit is set 00839 if (intSrc & (1<<6)) { 00840 return (intSrc & 0x3F); 00841 } 00842 00843 return 0; 00844 } 00845 00846 void LSM9DS1::configGyroInt(uint8_t generator, bool aoi, bool latch) 00847 { 00848 // Use variables from accel_interrupt_generator, OR'd together to create 00849 // the [generator]value. 00850 uint8_t temp = generator; 00851 if (aoi) temp |= 0x80; 00852 if (latch) temp |= 0x40; 00853 xgWriteByte(INT_GEN_CFG_G, temp); 00854 } 00855 00856 void LSM9DS1::configGyroThs(int16_t threshold, lsm9ds1_axis axis, uint8_t duration, bool wait) 00857 { 00858 uint8_t buffer[2]; 00859 buffer[0] = (threshold & 0x7F00) >> 8; 00860 buffer[1] = (threshold & 0x00FF); 00861 // Write threshold value to INT_GEN_THS_?H_G and INT_GEN_THS_?L_G. 00862 // axis will be 0, 1, or 2 (x, y, z respectively) 00863 xgWriteByte(INT_GEN_THS_XH_G + (axis * 2), buffer[0]); 00864 xgWriteByte(INT_GEN_THS_XH_G + 1 + (axis * 2), buffer[1]); 00865 00866 // Write duration and wait to INT_GEN_DUR_XL 00867 uint8_t temp; 00868 temp = (duration & 0x7F); 00869 if (wait) temp |= 0x80; 00870 xgWriteByte(INT_GEN_DUR_G, temp); 00871 } 00872 00873 uint8_t LSM9DS1::getGyroIntSrc() 00874 { 00875 uint8_t intSrc = xgReadByte(INT_GEN_SRC_G); 00876 00877 // Check if the IA_G (interrupt active) bit is set 00878 if (intSrc & (1<<6)) { 00879 return (intSrc & 0x3F); 00880 } 00881 00882 return 0; 00883 } 00884 00885 void LSM9DS1::configMagInt(uint8_t generator, h_lactive activeLow, bool latch) 00886 { 00887 // Mask out non-generator bits (0-4) 00888 uint8_t config = (generator & 0xE0); 00889 // IEA bit is 0 for active-low, 1 for active-high. 00890 if (activeLow == INT_ACTIVE_HIGH) config |= (1<<2); 00891 // IEL bit is 0 for latched, 1 for not-latched 00892 if (!latch) config |= (1<<1); 00893 // As long as we have at least 1 generator, enable the interrupt 00894 if (generator != 0) config |= (1<<0); 00895 00896 mWriteByte(INT_CFG_M, config); 00897 } 00898 00899 void LSM9DS1::configMagThs(uint16_t threshold) 00900 { 00901 // Write high eight bits of [threshold] to INT_THS_H_M 00902 mWriteByte(INT_THS_H_M, uint8_t((threshold & 0x7F00) >> 8)); 00903 // Write low eight bits of [threshold] to INT_THS_L_M 00904 mWriteByte(INT_THS_L_M, uint8_t(threshold & 0x00FF)); 00905 } 00906 00907 uint8_t LSM9DS1::getMagIntSrc() 00908 { 00909 uint8_t intSrc = mReadByte(INT_SRC_M); 00910 00911 // Check if the INT (interrupt active) bit is set 00912 if (intSrc & (1<<0)) { 00913 return (intSrc & 0xFE); 00914 } 00915 00916 return 0; 00917 } 00918 00919 void LSM9DS1::sleepGyro(bool enable) 00920 { 00921 uint8_t temp = xgReadByte(CTRL_REG9); 00922 if (enable) temp |= (1<<6); 00923 else temp &= ~(1<<6); 00924 xgWriteByte(CTRL_REG9, temp); 00925 } 00926 00927 void LSM9DS1::enableFIFO(bool enable) 00928 { 00929 uint8_t temp = xgReadByte(CTRL_REG9); 00930 if (enable) temp |= (1<<1); 00931 else temp &= ~(1<<1); 00932 xgWriteByte(CTRL_REG9, temp); 00933 } 00934 00935 void LSM9DS1::setFIFO(fifoMode_type fifoMode, uint8_t fifoThs) 00936 { 00937 // Limit threshold - 0x1F (31) is the maximum. If more than that was asked 00938 // limit it to the maximum. 00939 uint8_t threshold = fifoThs <= 0x1F ? fifoThs : 0x1F; 00940 xgWriteByte(FIFO_CTRL, ((fifoMode & 0x7) << 5) | (threshold & 0x1F)); 00941 } 00942 00943 uint8_t LSM9DS1::getFIFOSamples() 00944 { 00945 return (xgReadByte(FIFO_SRC) & 0x3F); 00946 } 00947 00948 void LSM9DS1::constrainScales() 00949 { 00950 if ((settings.gyro.scale != 245) && (settings.gyro.scale != 500) && 00951 (settings.gyro.scale != 2000)) { 00952 settings.gyro.scale = 245; 00953 } 00954 00955 if ((settings.accel.scale != 2) && (settings.accel.scale != 4) && 00956 (settings.accel.scale != 8) && (settings.accel.scale != 16)) { 00957 settings.accel.scale = 2; 00958 } 00959 00960 if ((settings.mag.scale != 4) && (settings.mag.scale != 8) && 00961 (settings.mag.scale != 12) && (settings.mag.scale != 16)) { 00962 settings.mag.scale = 4; 00963 } 00964 } 00965 00966 void LSM9DS1::xgWriteByte(uint8_t subAddress, uint8_t data) 00967 { 00968 // Whether we're using I2C or SPI, write a byte using the 00969 // gyro-specific I2C address or SPI CS pin. 00970 if (settings.device.commInterface == IMU_MODE_I2C) { 00971 pc.printf("yo"); 00972 I2CwriteByte(_xgAddress, subAddress, data); 00973 } else if (settings.device.commInterface == IMU_MODE_SPI) { 00974 SPIwriteByte(_xgAddress, subAddress, data); 00975 } 00976 } 00977 00978 void LSM9DS1::mWriteByte(uint8_t subAddress, uint8_t data) 00979 { 00980 // Whether we're using I2C or SPI, write a byte using the 00981 // accelerometer-specific I2C address or SPI CS pin. 00982 if (settings.device.commInterface == IMU_MODE_I2C) { 00983 pc.printf("mo"); 00984 return I2CwriteByte(_mAddress, subAddress, data); 00985 } else if (settings.device.commInterface == IMU_MODE_SPI) 00986 return SPIwriteByte(_mAddress, subAddress, data); 00987 } 00988 00989 uint8_t LSM9DS1::xgReadByte(uint8_t subAddress) 00990 { 00991 // Whether we're using I2C or SPI, read a byte using the 00992 // gyro-specific I2C address or SPI CS pin. 00993 if (settings.device.commInterface == IMU_MODE_I2C) 00994 return I2CreadByte(_xgAddress, subAddress); 00995 else if (settings.device.commInterface == IMU_MODE_SPI) 00996 return SPIreadByte(_xgAddress, subAddress); 00997 } 00998 00999 void LSM9DS1::xgReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) 01000 { 01001 // Whether we're using I2C or SPI, read multiple bytes using the 01002 // gyro-specific I2C address or SPI CS pin. 01003 if (settings.device.commInterface == IMU_MODE_I2C) { 01004 I2CreadBytes(_xgAddress, subAddress, dest, count); 01005 } else if (settings.device.commInterface == IMU_MODE_SPI) { 01006 SPIreadBytes(_xgAddress, subAddress, dest, count); 01007 } 01008 } 01009 01010 uint8_t LSM9DS1::mReadByte(uint8_t subAddress) 01011 { 01012 // Whether we're using I2C or SPI, read a byte using the 01013 // accelerometer-specific I2C address or SPI CS pin. 01014 if (settings.device.commInterface == IMU_MODE_I2C) 01015 return I2CreadByte(_mAddress, subAddress); 01016 else if (settings.device.commInterface == IMU_MODE_SPI) 01017 return SPIreadByte(_mAddress, subAddress); 01018 } 01019 01020 void LSM9DS1::mReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count) 01021 { 01022 // Whether we're using I2C or SPI, read multiple bytes using the 01023 // accelerometer-specific I2C address or SPI CS pin. 01024 if (settings.device.commInterface == IMU_MODE_I2C) 01025 I2CreadBytes(_mAddress, subAddress, dest, count); 01026 else if (settings.device.commInterface == IMU_MODE_SPI) 01027 SPIreadBytes(_mAddress, subAddress, dest, count); 01028 } 01029 01030 void LSM9DS1::initSPI() 01031 { 01032 /* 01033 pinMode(_xgAddress, OUTPUT); 01034 digitalWrite(_xgAddress, HIGH); 01035 pinMode(_mAddress, OUTPUT); 01036 digitalWrite(_mAddress, HIGH); 01037 01038 SPI.begin(); 01039 // Maximum SPI frequency is 10MHz, could divide by 2 here: 01040 SPI.setClockDivider(SPI_CLOCK_DIV2); 01041 // Data is read and written MSb first. 01042 SPI.setBitOrder(MSBFIRST); 01043 // Data is captured on rising edge of clock (CPHA = 0) 01044 // Base value of the clock is HIGH (CPOL = 1) 01045 SPI.setDataMode(SPI_MODE0); 01046 */ 01047 } 01048 01049 void LSM9DS1::SPIwriteByte(uint8_t csPin, uint8_t subAddress, uint8_t data) 01050 { 01051 /* 01052 digitalWrite(csPin, LOW); // Initiate communication 01053 01054 // If write, bit 0 (MSB) should be 0 01055 // If single write, bit 1 should be 0 01056 SPI.transfer(subAddress & 0x3F); // Send Address 01057 SPI.transfer(data); // Send data 01058 01059 digitalWrite(csPin, HIGH); // Close communication 01060 */ 01061 } 01062 01063 uint8_t LSM9DS1::SPIreadByte(uint8_t csPin, uint8_t subAddress) 01064 { 01065 uint8_t temp; 01066 // Use the multiple read function to read 1 byte. 01067 // Value is returned to `temp`. 01068 SPIreadBytes(csPin, subAddress, &temp, 1); 01069 return temp; 01070 } 01071 01072 void LSM9DS1::SPIreadBytes(uint8_t csPin, uint8_t subAddress, 01073 uint8_t * dest, uint8_t count) 01074 { 01075 // To indicate a read, set bit 0 (msb) of first byte to 1 01076 uint8_t rAddress = 0x80 | (subAddress & 0x3F); 01077 // Mag SPI port is different. If we're reading multiple bytes, 01078 // set bit 1 to 1. The remaining six bytes are the address to be read 01079 if ((csPin == _mAddress) && count > 1) 01080 rAddress |= 0x40; 01081 01082 /* 01083 digitalWrite(csPin, LOW); // Initiate communication 01084 SPI.transfer(rAddress); 01085 for (int i=0; i<count; i++) 01086 { 01087 dest[i] = SPI.transfer(0x00); // Read into destination array 01088 } 01089 digitalWrite(csPin, HIGH); // Close communication 01090 */ 01091 } 01092 01093 void LSM9DS1::initI2C() 01094 { 01095 /* 01096 Wire.begin(); // Initialize I2C library 01097 */ 01098 01099 //already initialized in constructor! 01100 } 01101 01102 // Wire.h read and write protocols 01103 void LSM9DS1::I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data) 01104 { 01105 /* 01106 Wire.beginTransmission(address); // Initialize the Tx buffer 01107 Wire.write(subAddress); // Put slave register address in Tx buffer 01108 Wire.write(data); // Put data in Tx buffer 01109 Wire.endTransmission(); // Send the Tx buffer 01110 */ 01111 char temp_data[2] = {subAddress, data}; 01112 i2c.write(address, temp_data, 2); 01113 } 01114 01115 uint8_t LSM9DS1::I2CreadByte(uint8_t address, uint8_t subAddress) 01116 { 01117 /* 01118 int timeout = LSM9DS1_COMMUNICATION_TIMEOUT; 01119 uint8_t data; // `data` will store the register data 01120 01121 Wire.beginTransmission(address); // Initialize the Tx buffer 01122 Wire.write(subAddress); // Put slave register address in Tx buffer 01123 Wire.endTransmission(true); // Send the Tx buffer, but send a restart to keep connection alive 01124 Wire.requestFrom(address, (uint8_t) 1); // Read one byte from slave register address 01125 while ((Wire.available() < 1) && (timeout-- > 0)) 01126 delay(1); 01127 01128 if (timeout <= 0) 01129 return 255; //! Bad! 255 will be misinterpreted as a good value. 01130 01131 data = Wire.read(); // Fill Rx buffer with result 01132 return data; // Return data read from slave register 01133 */ 01134 char data; 01135 char temp[2] = {subAddress}; 01136 01137 i2c.write(address, temp, 1); 01138 //i2c.write(address & 0xFE); 01139 temp[1] = 0x00; 01140 i2c.write(address, temp, 1); 01141 //i2c.write( address | 0x01); 01142 int a = i2c.read(address, &data, 1); 01143 return data; 01144 } 01145 01146 uint8_t LSM9DS1::I2CreadBytes(uint8_t address, uint8_t subAddress, uint8_t * dest, uint8_t count) 01147 { 01148 /* 01149 int timeout = LSM9DS1_COMMUNICATION_TIMEOUT; 01150 Wire.beginTransmission(address); // Initialize the Tx buffer 01151 // Next send the register to be read. OR with 0x80 to indicate multi-read. 01152 Wire.write(subAddress | 0x80); // Put slave register address in Tx buffer 01153 01154 Wire.endTransmission(true); // Send the Tx buffer, but send a restart to keep connection alive 01155 uint8_t i = 0; 01156 Wire.requestFrom(address, count); // Read bytes from slave register address 01157 while ((Wire.available() < count) && (timeout-- > 0)) 01158 delay(1); 01159 if (timeout <= 0) 01160 return -1; 01161 01162 for (int i=0; i<count;) 01163 { 01164 if (Wire.available()) 01165 { 01166 dest[i++] = Wire.read(); 01167 } 01168 } 01169 return count; 01170 */ 01171 int i; 01172 char temp_dest[count]; 01173 char temp[1] = {subAddress}; 01174 i2c.write(address, temp, 1); 01175 i2c.read(address, temp_dest, count); 01176 01177 //i2c doesn't take uint8_ts, but rather chars so do this nasty af conversion 01178 for (i=0; i < count; i++) { 01179 dest[i] = temp_dest[i]; 01180 } 01181 return count; 01182 }
Generated on Wed Jul 27 2022 05:25:39 by 1.7.2