altb_pmic / AHRS

Dependencies:   Eigen

Dependents:   IndNav_QK3_T265

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers LSM9DS1_i2c.cpp Source File

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