AdvRobot_Team / Mbed 2 deprecated LSM9DS1_Library

Dependencies:   PinDetect mbed

Fork of LSM9DS1_Library by jim hamblen

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers LSM9DS1.cpp Source File

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