Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: Eigen
LSM9DS1_i2c.h
00001 /****************************************************************************** 00002 SFE_LSM9DS1.h 00003 SFE_LSM9DS1 Library Header File 00004 Jim Lindblom @ SparkFun Electronics 00005 Original Creation Date: February 27, 2015 00006 https://github.com/sparkfun/LSM9DS1_Breakout 00007 00008 This file prototypes the LSM9DS1 class, implemented in SFE_LSM9DS1.cpp. In 00009 addition, it defines every register in the LSM9DS1 (both the Gyro and Accel/ 00010 Magnetometer registers). 00011 00012 Development environment specifics: 00013 IDE: Arduino 1.6.0 00014 Hardware Platform: Arduino Uno 00015 LSM9DS1 Breakout Version: 1.0 00016 00017 This code is beerware; if you see me (or any other SparkFun employee) at the 00018 local, and you've found our code helpful, please buy us a round! 00019 00020 Distributed as-is; no warranty is given. 00021 ******************************************************************************/ 00022 #ifndef __SparkFunLSM9DS1_H__ 00023 #define __SparkFunLSM9DS1_H__ 00024 00025 //#if defined(ARDUINO) && ARDUINO >= 100 00026 // #include "Arduino.h" 00027 //#else 00028 // #include "WProgram.h" 00029 // #include "pins_arduino.h" 00030 //#endif 00031 00032 #include "mbed.h" 00033 #include <stdint.h> 00034 #include "LSM9DS1_Registers.h" 00035 #include "LSM9DS1_Types.h" 00036 00037 #define LSM9DS1_AG_ADDR(sa0) ((sa0) == 0 ? 0x6A : 0x6B) 00038 #define LSM9DS1_M_ADDR(sa1) ((sa1) == 0 ? 0x1C : 0x1E) 00039 00040 enum lsm9ds1_axis { 00041 X_AXIS, 00042 Y_AXIS, 00043 Z_AXIS, 00044 ALL_AXIS 00045 }; 00046 00047 class LSM9DS1 00048 { 00049 public: 00050 IMUSettings settings; 00051 00052 // We'll store the gyro, accel, and magnetometer readings in a series of 00053 // public class variables. Each sensor gets three variables -- one for each 00054 // axis. Call readGyro(), readAccel(), and readMag() first, before using 00055 // these variables! 00056 // These values are the RAW signed 16-bit readings from the sensors. 00057 int16_t gx, gy, gz; // x, y, and z axis readings of the gyroscope 00058 int16_t ax, ay, az; // x, y, and z axis readings of the accelerometer 00059 int16_t mx, my, mz; // x, y, and z axis readings of the magnetometer 00060 int16_t temperature; // Chip temperature 00061 float gBias[3], aBias[3], mBias[3]; 00062 int16_t gBiasRaw[3], aBiasRaw[3], mBiasRaw[3]; 00063 00064 float gyroX, gyroY, gyroZ; // x, y, and z axis readings of the gyroscope (float value) 00065 float accX, accY, accZ; // x, y, and z axis readings of the accelerometer (float value) 00066 float magX, magY, magZ; // x, y, and z axis readings of the magnetometer (float value) 00067 00068 // LSM9DS1 -- LSM9DS1 class constructor 00069 // The constructor will set up a handful of private variables, and set the 00070 // communication mode as well. 00071 /**Input: 00072 * - interface = Either IMU_MODE_SPI or IMU_MODE_I2C, whichever you're using 00073 * to talk to the IC. 00074 * - xgAddr = If IMU_MODE_I2C, this is the I2C address of the accel/gyroscope. 00075 * If IMU_MODE_SPI, this is the chip select pin of the gyro (CS_AG) 00076 * - mAddr = If IMU_MODE_I2C, this is the I2C address of the magnetometer. 00077 * If IMU_MODE_SPI, this is the cs pin of the magnetometer (CS_M) 00078 00079 */ 00080 LSM9DS1(I2C &); 00081 //LSM9DS1(interface_mode interface, uint8_t xgAddr, uint8_t mAddr); 00082 //LSM9DS1(); 00083 00084 00085 /** begin() -- Initialize the gyro, accelerometer, and magnetometer. 00086 *This will set up the scale and output rate of each sensor. The values set 00087 * in the IMUSettings struct will take effect after calling this function. 00088 */ 00089 uint16_t begin(); 00090 00091 void calibrate(bool autoCalc = true); 00092 void calibrateMag(bool loadIn = true); 00093 void magOffset(uint8_t axis, int16_t offset); 00094 00095 /** accelAvailable() -- Polls the accelerometer status register to check 00096 * if new data is available. 00097 * Output: 1 - New data available 00098 * 0 - No new data available 00099 */ 00100 uint8_t accelAvailable(); 00101 00102 /** gyroAvailable() -- Polls the gyroscope status register to check 00103 * if new data is available. 00104 * Output: 1 - New data available 00105 * 0 - No new data available 00106 */ 00107 uint8_t gyroAvailable(); 00108 00109 /** gyroAvailable() -- Polls the temperature status register to check 00110 * if new data is available. 00111 * Output: 1 - New data available 00112 * 0 - No new data available 00113 */ 00114 uint8_t tempAvailable(); 00115 00116 /** magAvailable() -- Polls the accelerometer status register to check 00117 * if new data is available. 00118 * Input: 00119 * - axis can be either X_AXIS, Y_AXIS, Z_AXIS, to check for new data 00120 * on one specific axis. Or ALL_AXIS (default) to check for new data 00121 * on all axes. 00122 * Output: 1 - New data available 00123 * 0 - No new data available 00124 */ 00125 uint8_t magAvailable(lsm9ds1_axis axis = ALL_AXIS); 00126 00127 /** readGyro() -- Read the gyroscope output registers. 00128 * This function will read all six gyroscope output registers. 00129 * The readings are stored in the class' gx, gy, and gz variables. Read 00130 * those _after_ calling readGyro(). 00131 */ 00132 void readGyro(); 00133 00134 /** int16_t readGyro(axis) -- Read a specific axis of the gyroscope. 00135 * [axis] can be any of X_AXIS, Y_AXIS, or Z_AXIS. 00136 * Input: 00137 * - axis: can be either X_AXIS, Y_AXIS, or Z_AXIS. 00138 * Output: 00139 * A 16-bit signed integer with sensor data on requested axis. 00140 */ 00141 int16_t readGyro(lsm9ds1_axis axis); 00142 00143 /** readAccel() -- Read the accelerometer output registers. 00144 * This function will read all six accelerometer output registers. 00145 * The readings are stored in the class' ax, ay, and az variables. Read 00146 * those _after_ calling readAccel(). 00147 */ 00148 void readAccel(); 00149 00150 /** int16_t readAccel(axis) -- Read a specific axis of the accelerometer. 00151 * [axis] can be any of X_AXIS, Y_AXIS, or Z_AXIS. 00152 * Input: 00153 * - axis: can be either X_AXIS, Y_AXIS, or Z_AXIS. 00154 * Output: 00155 * A 16-bit signed integer with sensor data on requested axis. 00156 */ 00157 int16_t readAccel(lsm9ds1_axis axis); 00158 00159 /** readMag() -- Read the magnetometer output registers. 00160 * This function will read all six magnetometer output registers. 00161 * The readings are stored in the class' mx, my, and mz variables. Read 00162 * those _after_ calling readMag(). 00163 */ 00164 void readMag(); 00165 00166 /** int16_t readMag(axis) -- Read a specific axis of the magnetometer. 00167 * [axis] can be any of X_AXIS, Y_AXIS, or Z_AXIS. 00168 * Input: 00169 * - axis: can be either X_AXIS, Y_AXIS, or Z_AXIS. 00170 * Output: 00171 * A 16-bit signed integer with sensor data on requested axis. 00172 */ 00173 int16_t readMag(lsm9ds1_axis axis); 00174 00175 /** readTemp() -- Read the temperature output register. 00176 * This function will read two temperature output registers. 00177 * The combined readings are stored in the class' temperature variables. Read 00178 * those _after_ calling readTemp(). 00179 */ 00180 void readTemp(); 00181 00182 /** calcGyro() -- Convert from RAW signed 16-bit value to degrees per second 00183 * This function reads in a signed 16-bit value and returns the scaled 00184 * DPS. This function relies on gScale and gRes being correct. 00185 * Input: 00186 * - gyro = A signed 16-bit raw reading from the gyroscope. 00187 */ 00188 float calcGyro(int16_t gyro); 00189 00190 /** calcAccel() -- Convert from RAW signed 16-bit value to gravity (g's). 00191 * This function reads in a signed 16-bit value and returns the scaled 00192 * g's. This function relies on aScale and aRes being correct. 00193 * Input: 00194 * - accel = A signed 16-bit raw reading from the accelerometer. 00195 */ 00196 float calcAccel(int16_t accel); 00197 00198 /** calcMag() -- Convert from RAW signed 16-bit value to Gauss (Gs) 00199 * This function reads in a signed 16-bit value and returns the scaled 00200 * Gs. This function relies on mScale and mRes being correct. 00201 * Input: 00202 * - mag = A signed 16-bit raw reading from the magnetometer. 00203 */ 00204 float calcMag(int16_t mag); 00205 00206 /** setGyroScale() -- Set the full-scale range of the gyroscope. 00207 * This function can be called to set the scale of the gyroscope to 00208 * 245, 500, or 200 degrees per second. 00209 * Input: 00210 * - gScl = The desired gyroscope scale. Must be one of three possible 00211 * values from the gyro_scale. 00212 */ 00213 void setGyroScale(uint16_t gScl); 00214 00215 /** setAccelScale() -- Set the full-scale range of the accelerometer. 00216 * This function can be called to set the scale of the accelerometer to 00217 * 2, 4, 6, 8, or 16 g's. 00218 * Input: 00219 * - aScl = The desired accelerometer scale. Must be one of five possible 00220 * values from the accel_scale. 00221 */ 00222 void setAccelScale(uint8_t aScl); 00223 00224 /** setMagScale() -- Set the full-scale range of the magnetometer. 00225 * This function can be called to set the scale of the magnetometer to 00226 * 2, 4, 8, or 12 Gs. 00227 * Input: 00228 * - mScl = The desired magnetometer scale. Must be one of four possible 00229 * values from the mag_scale. 00230 */ 00231 void setMagScale(uint8_t mScl); 00232 00233 /** setGyroODR() -- Set the output data rate and bandwidth of the gyroscope 00234 * Input: 00235 * - gRate = The desired output rate and cutoff frequency of the gyro. 00236 */ 00237 void setGyroODR(uint8_t gRate); 00238 00239 // setAccelODR() -- Set the output data rate of the accelerometer 00240 // Input: 00241 // - aRate = The desired output rate of the accel. 00242 void setAccelODR(uint8_t aRate); 00243 00244 // setMagODR() -- Set the output data rate of the magnetometer 00245 // Input: 00246 // - mRate = The desired output rate of the mag. 00247 void setMagODR(uint8_t mRate); 00248 00249 // configInactivity() -- Configure inactivity interrupt parameters 00250 // Input: 00251 // - duration = Inactivity duration - actual value depends on gyro ODR 00252 // - threshold = Activity Threshold 00253 // - sleepOn = Gyroscope operating mode during inactivity. 00254 // true: gyroscope in sleep mode 00255 // false: gyroscope in power-down 00256 void configInactivity(uint8_t duration, uint8_t threshold, bool sleepOn); 00257 00258 // configAccelInt() -- Configure Accelerometer Interrupt Generator 00259 // Input: 00260 // - generator = Interrupt axis/high-low events 00261 // Any OR'd combination of ZHIE_XL, ZLIE_XL, YHIE_XL, YLIE_XL, XHIE_XL, XLIE_XL 00262 // - andInterrupts = AND/OR combination of interrupt events 00263 // true: AND combination 00264 // false: OR combination 00265 void configAccelInt(uint8_t generator, bool andInterrupts = false); 00266 00267 // configAccelThs() -- Configure the threshold of an accelereomter axis 00268 // Input: 00269 // - threshold = Interrupt threshold. Possible values: 0-255. 00270 // Multiply by 128 to get the actual raw accel value. 00271 // - axis = Axis to be configured. Either X_AXIS, Y_AXIS, or Z_AXIS 00272 // - duration = Duration value must be above or below threshold to trigger interrupt 00273 // - wait = Wait function on duration counter 00274 // true: Wait for duration samples before exiting interrupt 00275 // false: Wait function off 00276 void configAccelThs(uint8_t threshold, lsm9ds1_axis axis, uint8_t duration = 0, bool wait = 0); 00277 00278 // configGyroInt() -- Configure Gyroscope Interrupt Generator 00279 // Input: 00280 // - generator = Interrupt axis/high-low events 00281 // Any OR'd combination of ZHIE_G, ZLIE_G, YHIE_G, YLIE_G, XHIE_G, XLIE_G 00282 // - aoi = AND/OR combination of interrupt events 00283 // true: AND combination 00284 // false: OR combination 00285 // - latch: latch gyroscope interrupt request. 00286 void configGyroInt(uint8_t generator, bool aoi, bool latch); 00287 00288 // configGyroThs() -- Configure the threshold of a gyroscope axis 00289 // Input: 00290 // - threshold = Interrupt threshold. Possible values: 0-0x7FF. 00291 // Value is equivalent to raw gyroscope value. 00292 // - axis = Axis to be configured. Either X_AXIS, Y_AXIS, or Z_AXIS 00293 // - duration = Duration value must be above or below threshold to trigger interrupt 00294 // - wait = Wait function on duration counter 00295 // true: Wait for duration samples before exiting interrupt 00296 // false: Wait function off 00297 void configGyroThs(int16_t threshold, lsm9ds1_axis axis, uint8_t duration, bool wait); 00298 00299 // configInt() -- Configure INT1 or INT2 (Gyro and Accel Interrupts only) 00300 // Input: 00301 // - interrupt = Select INT1 or INT2 00302 // Possible values: XG_INT1 or XG_INT2 00303 // - generator = Or'd combination of interrupt generators. 00304 // Possible values: INT_DRDY_XL, INT_DRDY_G, INT1_BOOT (INT1 only), INT2_DRDY_TEMP (INT2 only) 00305 // INT_FTH, INT_OVR, INT_FSS5, INT_IG_XL (INT1 only), INT1_IG_G (INT1 only), INT2_INACT (INT2 only) 00306 // - activeLow = Interrupt active configuration 00307 // Can be either INT_ACTIVE_HIGH or INT_ACTIVE_LOW 00308 // - pushPull = Push-pull or open drain interrupt configuration 00309 // Can be either INT_PUSH_PULL or INT_OPEN_DRAIN 00310 void configInt(interrupt_select interupt, uint8_t generator, 00311 h_lactive activeLow = INT_ACTIVE_LOW, pp_od pushPull = INT_PUSH_PULL); 00312 00313 /** configMagInt() -- Configure Magnetometer Interrupt Generator 00314 * Input: 00315 * - generator = Interrupt axis/high-low events 00316 * Any OR'd combination of ZIEN, YIEN, XIEN 00317 * - activeLow = Interrupt active configuration 00318 * Can be either INT_ACTIVE_HIGH or INT_ACTIVE_LOW 00319 * - latch: latch gyroscope interrupt request. 00320 */ 00321 void configMagInt(uint8_t generator, h_lactive activeLow, bool latch = true); 00322 00323 /** configMagThs() -- Configure the threshold of a gyroscope axis 00324 * Input: 00325 * - threshold = Interrupt threshold. Possible values: 0-0x7FF. 00326 * Value is equivalent to raw magnetometer value. 00327 */ 00328 void configMagThs(uint16_t threshold); 00329 00330 //! getGyroIntSrc() -- Get contents of Gyroscope interrupt source register 00331 uint8_t getGyroIntSrc(); 00332 00333 //! getGyroIntSrc() -- Get contents of accelerometer interrupt source register 00334 uint8_t getAccelIntSrc(); 00335 00336 //! getGyroIntSrc() -- Get contents of magnetometer interrupt source register 00337 uint8_t getMagIntSrc(); 00338 00339 //! getGyroIntSrc() -- Get status of inactivity interrupt 00340 uint8_t getInactivity(); 00341 00342 /** sleepGyro() -- Sleep or wake the gyroscope 00343 * Input: 00344 * - enable: True = sleep gyro. False = wake gyro. 00345 */ 00346 void sleepGyro(bool enable = true); 00347 00348 /** enableFIFO() - Enable or disable the FIFO 00349 * Input: 00350 * - enable: true = enable, false = disable. 00351 */ 00352 void enableFIFO(bool enable = true); 00353 00354 /** setFIFO() - Configure FIFO mode and Threshold 00355 * Input: 00356 * - fifoMode: Set FIFO mode to off, FIFO (stop when full), continuous, bypass 00357 * Possible inputs: FIFO_OFF, FIFO_THS, FIFO_CONT_TRIGGER, FIFO_OFF_TRIGGER, FIFO_CONT 00358 * - fifoThs: FIFO threshold level setting 00359 * Any value from 0-0x1F is acceptable. 00360 */ 00361 void setFIFO(fifoMode_type fifoMode, uint8_t fifoThs); 00362 00363 //! getFIFOSamples() - Get number of FIFO samples 00364 uint8_t getFIFOSamples(); 00365 00366 00367 protected: 00368 // x_mAddress and gAddress store the I2C address or SPI chip select pin 00369 // for each sensor. 00370 uint8_t _mAddress, _xgAddress; 00371 00372 // gRes, aRes, and mRes store the current resolution for each sensor. 00373 // Units of these values would be DPS (or g's or Gs's) per ADC tick. 00374 // This value is calculated as (sensor scale) / (2^15). 00375 float gRes, aRes, mRes; 00376 00377 // _autoCalc keeps track of whether we're automatically subtracting off 00378 // accelerometer and gyroscope bias calculated in calibrate(). 00379 bool _autoCalc; 00380 00381 // init() -- Sets up gyro, accel, and mag settings to default. 00382 // - interface - Sets the interface mode (IMU_MODE_I2C or IMU_MODE_SPI) 00383 // - xgAddr - Sets either the I2C address of the accel/gyro or SPI chip 00384 // select pin connected to the CS_XG pin. 00385 // - mAddr - Sets either the I2C address of the magnetometer or SPI chip 00386 // select pin connected to the CS_M pin. 00387 void init(interface_mode interface, uint8_t xgAddr, uint8_t mAddr); 00388 00389 // initGyro() -- Sets up the gyroscope to begin reading. 00390 // This function steps through all five gyroscope control registers. 00391 // Upon exit, the following parameters will be set: 00392 // - CTRL_REG1_G = 0x0F: Normal operation mode, all axes enabled. 00393 // 95 Hz ODR, 12.5 Hz cutoff frequency. 00394 // - CTRL_REG2_G = 0x00: HPF set to normal mode, cutoff frequency 00395 // set to 7.2 Hz (depends on ODR). 00396 // - CTRL_REG3_G = 0x88: Interrupt enabled on INT_G (set to push-pull and 00397 // active high). Data-ready output enabled on DRDY_G. 00398 // - CTRL_REG4_G = 0x00: Continuous update mode. Data LSB stored in lower 00399 // address. Scale set to 245 DPS. SPI mode set to 4-wire. 00400 // - CTRL_REG5_G = 0x00: FIFO disabled. HPF disabled. 00401 void initGyro(); 00402 00403 // initAccel() -- Sets up the accelerometer to begin reading. 00404 // This function steps through all accelerometer related control registers. 00405 // Upon exit these registers will be set as: 00406 // - CTRL_REG0_XM = 0x00: FIFO disabled. HPF bypassed. Normal mode. 00407 // - CTRL_REG1_XM = 0x57: 100 Hz data rate. Continuous update. 00408 // all axes enabled. 00409 // - CTRL_REG2_XM = 0x00: 2g scale. 773 Hz anti-alias filter BW. 00410 // - CTRL_REG3_XM = 0x04: Accel data ready signal on INT1_XM pin. 00411 void initAccel(); 00412 00413 // initMag() -- Sets up the magnetometer to begin reading. 00414 // This function steps through all magnetometer-related control registers. 00415 // Upon exit these registers will be set as: 00416 // - CTRL_REG4_XM = 0x04: Mag data ready signal on INT2_XM pin. 00417 // - CTRL_REG5_XM = 0x14: 100 Hz update rate. Low resolution. Interrupt 00418 // requests don't latch. Temperature sensor disabled. 00419 // - CTRL_REG6_XM = 0x00: 2 Gs scale. 00420 // - CTRL_REG7_XM = 0x00: Continuous conversion mode. Normal HPF mode. 00421 // - INT_CTRL_REG_M = 0x09: Interrupt active-high. Enable interrupts. 00422 void initMag(); 00423 00424 // gReadByte() -- Reads a byte from a specified gyroscope register. 00425 // Input: 00426 // - subAddress = Register to be read from. 00427 // Output: 00428 // - An 8-bit value read from the requested address. 00429 uint8_t mReadByte(uint8_t subAddress); 00430 00431 // gReadBytes() -- Reads a number of bytes -- beginning at an address 00432 // and incrementing from there -- from the gyroscope. 00433 // Input: 00434 // - subAddress = Register to be read from. 00435 // - * dest = A pointer to an array of uint8_t's. Values read will be 00436 // stored in here on return. 00437 // - count = The number of bytes to be read. 00438 // Output: No value is returned, but the `dest` array will store 00439 // the data read upon exit. 00440 void mReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count); 00441 00442 // gWriteByte() -- Write a byte to a register in the gyroscope. 00443 // Input: 00444 // - subAddress = Register to be written to. 00445 // - data = data to be written to the register. 00446 void mWriteByte(uint8_t subAddress, uint8_t data); 00447 00448 // xmReadByte() -- Read a byte from a register in the accel/mag sensor 00449 // Input: 00450 // - subAddress = Register to be read from. 00451 // Output: 00452 // - An 8-bit value read from the requested register. 00453 uint8_t xgReadByte(uint8_t subAddress); 00454 00455 // xmReadBytes() -- Reads a number of bytes -- beginning at an address 00456 // and incrementing from there -- from the accelerometer/magnetometer. 00457 // Input: 00458 // - subAddress = Register to be read from. 00459 // - * dest = A pointer to an array of uint8_t's. Values read will be 00460 // stored in here on return. 00461 // - count = The number of bytes to be read. 00462 // Output: No value is returned, but the `dest` array will store 00463 // the data read upon exit. 00464 void xgReadBytes(uint8_t subAddress, uint8_t * dest, uint8_t count); 00465 00466 // xmWriteByte() -- Write a byte to a register in the accel/mag sensor. 00467 // Input: 00468 // - subAddress = Register to be written to. 00469 // - data = data to be written to the register. 00470 void xgWriteByte(uint8_t subAddress, uint8_t data); 00471 00472 // calcgRes() -- Calculate the resolution of the gyroscope. 00473 // This function will set the value of the gRes variable. gScale must 00474 // be set prior to calling this function. 00475 void calcgRes(); 00476 00477 // calcmRes() -- Calculate the resolution of the magnetometer. 00478 // This function will set the value of the mRes variable. mScale must 00479 // be set prior to calling this function. 00480 void calcmRes(); 00481 00482 // calcaRes() -- Calculate the resolution of the accelerometer. 00483 // This function will set the value of the aRes variable. aScale must 00484 // be set prior to calling this function. 00485 void calcaRes(); 00486 00487 ////////////////////// 00488 // Helper Functions // 00489 ////////////////////// 00490 void constrainScales(); 00491 00492 /////////////////// 00493 // SPI Functions // 00494 /////////////////// 00495 // initSPI() -- Initialize the SPI hardware. 00496 // This function will setup all SPI pins and related hardware. 00497 void initSPI(); 00498 00499 // SPIwriteByte() -- Write a byte out of SPI to a register in the device 00500 // Input: 00501 // - csPin = The chip select pin of the slave device. 00502 // - subAddress = The register to be written to. 00503 // - data = Byte to be written to the register. 00504 void SPIwriteByte(uint8_t csPin, uint8_t subAddress, uint8_t data); 00505 00506 // SPIreadByte() -- Read a single byte from a register over SPI. 00507 // Input: 00508 // - csPin = The chip select pin of the slave device. 00509 // - subAddress = The register to be read from. 00510 // Output: 00511 // - The byte read from the requested address. 00512 uint8_t SPIreadByte(uint8_t csPin, uint8_t subAddress); 00513 00514 // SPIreadBytes() -- Read a series of bytes, starting at a register via SPI 00515 // Input: 00516 // - csPin = The chip select pin of a slave device. 00517 // - subAddress = The register to begin reading. 00518 // - * dest = Pointer to an array where we'll store the readings. 00519 // - count = Number of registers to be read. 00520 // Output: No value is returned by the function, but the registers read are 00521 // all stored in the *dest array given. 00522 void SPIreadBytes(uint8_t csPin, uint8_t subAddress, 00523 uint8_t * dest, uint8_t count); 00524 00525 /////////////////// 00526 // I2C Functions // 00527 /////////////////// 00528 // initI2C() -- Initialize the I2C hardware. 00529 // This function will setup all I2C pins and related hardware. 00530 void initI2C(); 00531 00532 // I2CwriteByte() -- Write a byte out of I2C to a register in the device 00533 // Input: 00534 // - address = The 7-bit I2C address of the slave device. 00535 // - subAddress = The register to be written to. 00536 // - data = Byte to be written to the register. 00537 void I2CwriteByte(uint8_t address, uint8_t subAddress, uint8_t data); 00538 00539 // I2CreadByte() -- Read a single byte from a register over I2C. 00540 // Input: 00541 // - address = The 7-bit I2C address of the slave device. 00542 // - subAddress = The register to be read from. 00543 // Output: 00544 // - The byte read from the requested address. 00545 uint8_t I2CreadByte(uint8_t address, uint8_t subAddress); 00546 00547 // I2CreadBytes() -- Read a series of bytes, starting at a register via SPI 00548 // Input: 00549 // - address = The 7-bit I2C address of the slave device. 00550 // - subAddress = The register to begin reading. 00551 // - * dest = Pointer to an array where we'll store the readings. 00552 // - count = Number of registers to be read. 00553 // Output: No value is returned by the function, but the registers read are 00554 // all stored in the *dest array given. 00555 uint8_t I2CreadBytes(uint8_t address, uint8_t subAddress, uint8_t * dest, uint8_t count); 00556 00557 private: 00558 I2C &i2c; 00559 }; 00560 00561 #endif // SFE_LSM9DS1_H // 00562
Generated on Thu Jul 14 2022 22:08:52 by
1.7.2