From bd45987fe058b4220fe1122143ee5b6bb976af88 Mon Sep 17 00:00:00 2001 From: Thomas Chou Date: Wed, 8 May 2024 13:04:12 -0700 Subject: [PATCH] imu: use mpu6050 driver for mpu9150 The mpu9150 integrates mpu6050 and ak8975. There is no need to provide separate drivers. Signed-off-by: Thomas Chou --- firmware/lib/imu/MPU9150.cpp | 3167 -------------------------------- firmware/lib/imu/MPU9150.h | 1040 ----------- firmware/lib/imu/default_imu.h | 55 - firmware/lib/imu/imu.h | 8 +- 4 files changed, 4 insertions(+), 4266 deletions(-) delete mode 100644 firmware/lib/imu/MPU9150.cpp delete mode 100644 firmware/lib/imu/MPU9150.h diff --git a/firmware/lib/imu/MPU9150.cpp b/firmware/lib/imu/MPU9150.cpp deleted file mode 100644 index 689a856b..00000000 --- a/firmware/lib/imu/MPU9150.cpp +++ /dev/null @@ -1,3167 +0,0 @@ -// I2Cdev library collection - MPU9150 I2C device class -// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) -// 8/24/2011 by Jeff Rowberg -// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib -// -// Changelog: -// ... - ongoing debug release - -// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE -// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF -// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. - -/* ============================================ -I2Cdev device library code is placed under the MIT license -Copyright (c) 2012 Jeff Rowberg - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in -all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN -THE SOFTWARE. -=============================================== -*/ - -#include "MPU9150.h" - -/** Default constructor, uses default I2C address. - * @see MPU9150_DEFAULT_ADDRESS - */ -MPU9150::MPU9150() { - devAddr = MPU9150_DEFAULT_ADDRESS; -} - -/** Specific address constructor. - * @param address I2C address - * @see MPU9150_DEFAULT_ADDRESS - * @see MPU9150_ADDRESS_AD0_LOW - * @see MPU9150_ADDRESS_AD0_HIGH - */ -MPU9150::MPU9150(uint8_t address) { - devAddr = address; -} - -/** Power on and prepare for general usage. - * This will activate the device and take it out of sleep mode (which must be done - * after start-up). This function also sets both the accelerometer and the gyroscope - * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets - * the clock source to use the X Gyro for reference, which is slightly better than - * the default internal clock source. - */ -void MPU9150::initialize() { - setClockSource(MPU9150_CLOCK_PLL_XGYRO); - setFullScaleGyroRange(MPU9150_GYRO_FS_250); - setFullScaleAccelRange(MPU9150_ACCEL_FS_2); - setSleepEnabled(false); // thanks to Jack Elston for pointing this one out! -} - -/** Verify the I2C connection. - * Make sure the device is connected and responds as expected. - * @return True if connection is valid, false otherwise - */ -bool MPU9150::testConnection() { - return getDeviceID() == 0x34; -} - -// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC) - -/** Get the auxiliary I2C supply voltage level. - * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to - * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to - * the MPU-6000, which does not have a VLOGIC pin. - * @return I2C supply voltage level (0=VLOGIC, 1=VDD) - */ -uint8_t MPU9150::getAuxVDDIOLevel() { - I2Cdev::readBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_PWR_MODE_BIT, buffer); - return buffer[0]; -} -/** Set the auxiliary I2C supply voltage level. - * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to - * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to - * the MPU-6000, which does not have a VLOGIC pin. - * @param level I2C supply voltage level (0=VLOGIC, 1=VDD) - */ -void MPU9150::setAuxVDDIOLevel(uint8_t level) { - I2Cdev::writeBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_PWR_MODE_BIT, level); -} - -// SMPLRT_DIV register - -/** Get gyroscope output rate divider. - * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero - * Motion detection, and Free Fall detection are all based on the Sample Rate. - * The Sample Rate is generated by dividing the gyroscope output rate by - * SMPLRT_DIV: - * - * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) - * - * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or - * 7), and 1kHz when the DLPF is enabled (see Register 26). - * - * Note: The accelerometer output rate is 1kHz. This means that for a Sample - * Rate greater than 1kHz, the same accelerometer sample may be output to the - * FIFO, DMP, and sensor registers more than once. - * - * For a diagram of the gyroscope and accelerometer signal paths, see Section 8 - * of the MPU-6000/MPU-9150 Product Specification document. - * - * @return Current sample rate - * @see MPU9150_RA_SMPLRT_DIV - */ -uint8_t MPU9150::getRate() { - I2Cdev::readByte(devAddr, MPU9150_RA_SMPLRT_DIV, buffer); - return buffer[0]; -} -/** Set gyroscope sample rate divider. - * @param rate New sample rate divider - * @see getRate() - * @see MPU9150_RA_SMPLRT_DIV - */ -void MPU9150::setRate(uint8_t rate) { - I2Cdev::writeByte(devAddr, MPU9150_RA_SMPLRT_DIV, rate); -} - -// CONFIG register - -/** Get external FSYNC configuration. - * Configures the external Frame Synchronization (FSYNC) pin sampling. An - * external signal connected to the FSYNC pin can be sampled by configuring - * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short - * strobes may be captured. The latched FSYNC signal will be sampled at the - * Sampling Rate, as defined in register 25. After sampling, the latch will - * reset to the current FSYNC signal state. - * - * The sampled value will be reported in place of the least significant bit in - * a sensor data register determined by the value of EXT_SYNC_SET according to - * the following table. - * - *
- * EXT_SYNC_SET | FSYNC Bit Location
- * -------------+-------------------
- * 0            | Input disabled
- * 1            | TEMP_OUT_L[0]
- * 2            | GYRO_XOUT_L[0]
- * 3            | GYRO_YOUT_L[0]
- * 4            | GYRO_ZOUT_L[0]
- * 5            | ACCEL_XOUT_L[0]
- * 6            | ACCEL_YOUT_L[0]
- * 7            | ACCEL_ZOUT_L[0]
- * 
- * - * @return FSYNC configuration value - */ -uint8_t MPU9150::getExternalFrameSync() { - I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_CFG_EXT_SYNC_SET_LENGTH, buffer); - return buffer[0]; -} -/** Set external FSYNC configuration. - * @see getExternalFrameSync() - * @see MPU9150_RA_CONFIG - * @param sync New FSYNC configuration value - */ -void MPU9150::setExternalFrameSync(uint8_t sync) { - I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_CFG_EXT_SYNC_SET_LENGTH, sync); -} -/** Get digital low-pass filter configuration. - * The DLPF_CFG parameter sets the digital low pass filter configuration. It - * also determines the internal sampling rate used by the device as shown in - * the table below. - * - * Note: The accelerometer output rate is 1kHz. This means that for a Sample - * Rate greater than 1kHz, the same accelerometer sample may be output to the - * FIFO, DMP, and sensor registers more than once. - * - *
- *          |   ACCELEROMETER    |           GYROSCOPE
- * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
- * ---------+-----------+--------+-----------+--------+-------------
- * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
- * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
- * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
- * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
- * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
- * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
- * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
- * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
- * 
- * - * @return DLFP configuration - * @see MPU9150_RA_CONFIG - * @see MPU9150_CFG_DLPF_CFG_BIT - * @see MPU9150_CFG_DLPF_CFG_LENGTH - */ -uint8_t MPU9150::getDLPFMode() { - I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_CFG_DLPF_CFG_LENGTH, buffer); - return buffer[0]; -} -/** Set digital low-pass filter configuration. - * @param mode New DLFP configuration setting - * @see getDLPFBandwidth() - * @see MPU9150_DLPF_BW_256 - * @see MPU9150_RA_CONFIG - * @see MPU9150_CFG_DLPF_CFG_BIT - * @see MPU9150_CFG_DLPF_CFG_LENGTH - */ -void MPU9150::setDLPFMode(uint8_t mode) { - I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_CFG_DLPF_CFG_LENGTH, mode); -} - -// GYRO_CONFIG register - -/** Get full-scale gyroscope range. - * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, - * as described in the table below. - * - *
- * 0 = +/- 250 degrees/sec
- * 1 = +/- 500 degrees/sec
- * 2 = +/- 1000 degrees/sec
- * 3 = +/- 2000 degrees/sec
- * 
- * - * @return Current full-scale gyroscope range setting - * @see MPU9150_GYRO_FS_250 - * @see MPU9150_RA_GYRO_CONFIG - * @see MPU9150_GCONFIG_FS_SEL_BIT - * @see MPU9150_GCONFIG_FS_SEL_LENGTH - */ -uint8_t MPU9150::getFullScaleGyroRange() { - I2Cdev::readBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, buffer); - return buffer[0]; -} -/** Set full-scale gyroscope range. - * @param range New full-scale gyroscope range value - * @see getFullScaleRange() - * @see MPU9150_GYRO_FS_250 - * @see MPU9150_RA_GYRO_CONFIG - * @see MPU9150_GCONFIG_FS_SEL_BIT - * @see MPU9150_GCONFIG_FS_SEL_LENGTH - */ -void MPU9150::setFullScaleGyroRange(uint8_t range) { - I2Cdev::writeBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, range); -} - -// ACCEL_CONFIG register - -/** Get self-test enabled setting for accelerometer X axis. - * @return Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -bool MPU9150::getAccelXSelfTest() { - I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, buffer); - return buffer[0]; -} -/** Get self-test enabled setting for accelerometer X axis. - * @param enabled Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -void MPU9150::setAccelXSelfTest(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, enabled); -} -/** Get self-test enabled value for accelerometer Y axis. - * @return Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -bool MPU9150::getAccelYSelfTest() { - I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, buffer); - return buffer[0]; -} -/** Get self-test enabled value for accelerometer Y axis. - * @param enabled Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -void MPU9150::setAccelYSelfTest(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, enabled); -} -/** Get self-test enabled value for accelerometer Z axis. - * @return Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -bool MPU9150::getAccelZSelfTest() { - I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ZA_ST_BIT, buffer); - return buffer[0]; -} -/** Set self-test enabled value for accelerometer Z axis. - * @param enabled Self-test enabled value - * @see MPU9150_RA_ACCEL_CONFIG - */ -void MPU9150::setAccelZSelfTest(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ZA_ST_BIT, enabled); -} -/** Get full-scale accelerometer range. - * The FS_SEL parameter allows setting the full-scale range of the accelerometer - * sensors, as described in the table below. - * - *
- * 0 = +/- 2g
- * 1 = +/- 4g
- * 2 = +/- 8g
- * 3 = +/- 16g
- * 
- * - * @return Current full-scale accelerometer range setting - * @see MPU9150_ACCEL_FS_2 - * @see MPU9150_RA_ACCEL_CONFIG - * @see MPU9150_ACONFIG_AFS_SEL_BIT - * @see MPU9150_ACONFIG_AFS_SEL_LENGTH - */ -uint8_t MPU9150::getFullScaleAccelRange() { - I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_ACONFIG_AFS_SEL_LENGTH, buffer); - return buffer[0]; -} -/** Set full-scale accelerometer range. - * @param range New full-scale accelerometer range setting - * @see getFullScaleAccelRange() - */ -void MPU9150::setFullScaleAccelRange(uint8_t range) { - I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_ACONFIG_AFS_SEL_LENGTH, range); -} -/** Get the high-pass filter configuration. - * The DHPF is a filter module in the path leading to motion detectors (Free - * Fall, Motion threshold, and Zero Motion). The high pass filter output is not - * available to the data registers (see Figure in Section 8 of the MPU-6000/ - * MPU-9150 Product Specification document). - * - * The high pass filter has three modes: - * - *
- *    Reset: The filter output settles to zero within one sample. This
- *           effectively disables the high pass filter. This mode may be toggled
- *           to quickly settle the filter.
- *
- *    On:    The high pass filter will pass signals above the cut off frequency.
- *
- *    Hold:  When triggered, the filter holds the present sample. The filter
- *           output will be the difference between the input sample and the held
- *           sample.
- * 
- * - *
- * ACCEL_HPF | Filter Mode | Cut-off Frequency
- * ----------+-------------+------------------
- * 0         | Reset       | None
- * 1         | On          | 5Hz
- * 2         | On          | 2.5Hz
- * 3         | On          | 1.25Hz
- * 4         | On          | 0.63Hz
- * 7         | Hold        | None
- * 
- * - * @return Current high-pass filter configuration - * @see MPU9150_DHPF_RESET - * @see MPU9150_RA_ACCEL_CONFIG - */ -uint8_t MPU9150::getDHPFMode() { - I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_ACONFIG_ACCEL_HPF_LENGTH, buffer); - return buffer[0]; -} -/** Set the high-pass filter configuration. - * @param bandwidth New high-pass filter configuration - * @see setDHPFMode() - * @see MPU9150_DHPF_RESET - * @see MPU9150_RA_ACCEL_CONFIG - */ -void MPU9150::setDHPFMode(uint8_t bandwidth) { - I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_ACONFIG_ACCEL_HPF_LENGTH, bandwidth); -} - -// FF_THR register - -/** Get free-fall event acceleration threshold. - * This register configures the detection threshold for Free Fall event - * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the - * absolute value of the accelerometer measurements for the three axes are each - * less than the detection threshold. This condition increments the Free Fall - * duration counter (Register 30). The Free Fall interrupt is triggered when the - * Free Fall duration counter reaches the time specified in FF_DUR. - * - * For more details on the Free Fall detection interrupt, see Section 8.2 of the - * MPU-6000/MPU-9150 Product Specification document as well as Registers 56 and - * 58 of this document. - * - * @return Current free-fall acceleration threshold value (LSB = 2mg) - * @see MPU9150_RA_FF_THR - */ -uint8_t MPU9150::getFreefallDetectionThreshold() { - I2Cdev::readByte(devAddr, MPU9150_RA_FF_THR, buffer); - return buffer[0]; -} -/** Get free-fall event acceleration threshold. - * @param threshold New free-fall acceleration threshold value (LSB = 2mg) - * @see getFreefallDetectionThreshold() - * @see MPU9150_RA_FF_THR - */ -void MPU9150::setFreefallDetectionThreshold(uint8_t threshold) { - I2Cdev::writeByte(devAddr, MPU9150_RA_FF_THR, threshold); -} - -// FF_DUR register - -/** Get free-fall event duration threshold. - * This register configures the duration counter threshold for Free Fall event - * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit - * of 1 LSB = 1 ms. - * - * The Free Fall duration counter increments while the absolute value of the - * accelerometer measurements are each less than the detection threshold - * (Register 29). The Free Fall interrupt is triggered when the Free Fall - * duration counter reaches the time specified in this register. - * - * For more details on the Free Fall detection interrupt, see Section 8.2 of - * the MPU-6000/MPU-9150 Product Specification document as well as Registers 56 - * and 58 of this document. - * - * @return Current free-fall duration threshold value (LSB = 1ms) - * @see MPU9150_RA_FF_DUR - */ -uint8_t MPU9150::getFreefallDetectionDuration() { - I2Cdev::readByte(devAddr, MPU9150_RA_FF_DUR, buffer); - return buffer[0]; -} -/** Get free-fall event duration threshold. - * @param duration New free-fall duration threshold value (LSB = 1ms) - * @see getFreefallDetectionDuration() - * @see MPU9150_RA_FF_DUR - */ -void MPU9150::setFreefallDetectionDuration(uint8_t duration) { - I2Cdev::writeByte(devAddr, MPU9150_RA_FF_DUR, duration); -} - -// MOT_THR register - -/** Get motion detection event acceleration threshold. - * This register configures the detection threshold for Motion interrupt - * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the - * absolute value of any of the accelerometer measurements exceeds this Motion - * detection threshold. This condition increments the Motion detection duration - * counter (Register 32). The Motion detection interrupt is triggered when the - * Motion Detection counter reaches the time count specified in MOT_DUR - * (Register 32). - * - * The Motion interrupt will indicate the axis and polarity of detected motion - * in MOT_DETECT_STATUS (Register 97). - * - * For more details on the Motion detection interrupt, see Section 8.3 of the - * MPU-6000/MPU-9150 Product Specification document as well as Registers 56 and - * 58 of this document. - * - * @return Current motion detection acceleration threshold value (LSB = 2mg) - * @see MPU9150_RA_MOT_THR - */ -uint8_t MPU9150::getMotionDetectionThreshold() { - I2Cdev::readByte(devAddr, MPU9150_RA_MOT_THR, buffer); - return buffer[0]; -} -/** Set free-fall event acceleration threshold. - * @param threshold New motion detection acceleration threshold value (LSB = 2mg) - * @see getMotionDetectionThreshold() - * @see MPU9150_RA_MOT_THR - */ -void MPU9150::setMotionDetectionThreshold(uint8_t threshold) { - I2Cdev::writeByte(devAddr, MPU9150_RA_MOT_THR, threshold); -} - -// MOT_DUR register - -/** Get motion detection event duration threshold. - * This register configures the duration counter threshold for Motion interrupt - * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit - * of 1LSB = 1ms. The Motion detection duration counter increments when the - * absolute value of any of the accelerometer measurements exceeds the Motion - * detection threshold (Register 31). The Motion detection interrupt is - * triggered when the Motion detection counter reaches the time count specified - * in this register. - * - * For more details on the Motion detection interrupt, see Section 8.3 of the - * MPU-6000/MPU-9150 Product Specification document. - * - * @return Current motion detection duration threshold value (LSB = 1ms) - * @see MPU9150_RA_MOT_DUR - */ -uint8_t MPU9150::getMotionDetectionDuration() { - I2Cdev::readByte(devAddr, MPU9150_RA_MOT_DUR, buffer); - return buffer[0]; -} -/** Set motion detection event duration threshold. - * @param duration New motion detection duration threshold value (LSB = 1ms) - * @see getMotionDetectionDuration() - * @see MPU9150_RA_MOT_DUR - */ -void MPU9150::setMotionDetectionDuration(uint8_t duration) { - I2Cdev::writeByte(devAddr, MPU9150_RA_MOT_DUR, duration); -} - -// ZRMOT_THR register - -/** Get zero motion detection event acceleration threshold. - * This register configures the detection threshold for Zero Motion interrupt - * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when - * the absolute value of the accelerometer measurements for the 3 axes are each - * less than the detection threshold. This condition increments the Zero Motion - * duration counter (Register 34). The Zero Motion interrupt is triggered when - * the Zero Motion duration counter reaches the time count specified in - * ZRMOT_DUR (Register 34). - * - * Unlike Free Fall or Motion detection, Zero Motion detection triggers an - * interrupt both when Zero Motion is first detected and when Zero Motion is no - * longer detected. - * - * When a zero motion event is detected, a Zero Motion Status will be indicated - * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion - * condition is detected, the status bit is set to 1. When a zero-motion-to- - * motion condition is detected, the status bit is set to 0. - * - * For more details on the Zero Motion detection interrupt, see Section 8.4 of - * the MPU-6000/MPU-9150 Product Specification document as well as Registers 56 - * and 58 of this document. - * - * @return Current zero motion detection acceleration threshold value (LSB = 2mg) - * @see MPU9150_RA_ZRMOT_THR - */ -uint8_t MPU9150::getZeroMotionDetectionThreshold() { - I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_THR, buffer); - return buffer[0]; -} -/** Set zero motion detection event acceleration threshold. - * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) - * @see getZeroMotionDetectionThreshold() - * @see MPU9150_RA_ZRMOT_THR - */ -void MPU9150::setZeroMotionDetectionThreshold(uint8_t threshold) { - I2Cdev::writeByte(devAddr, MPU9150_RA_ZRMOT_THR, threshold); -} - -// ZRMOT_DUR register - -/** Get zero motion detection event duration threshold. - * This register configures the duration counter threshold for Zero Motion - * interrupt generation. The duration counter ticks at 16 Hz, therefore - * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter - * increments while the absolute value of the accelerometer measurements are - * each less than the detection threshold (Register 33). The Zero Motion - * interrupt is triggered when the Zero Motion duration counter reaches the time - * count specified in this register. - * - * For more details on the Zero Motion detection interrupt, see Section 8.4 of - * the MPU-6000/MPU-9150 Product Specification document, as well as Registers 56 - * and 58 of this document. - * - * @return Current zero motion detection duration threshold value (LSB = 64ms) - * @see MPU9150_RA_ZRMOT_DUR - */ -uint8_t MPU9150::getZeroMotionDetectionDuration() { - I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_DUR, buffer); - return buffer[0]; -} -/** Set zero motion detection event duration threshold. - * @param duration New zero motion detection duration threshold value (LSB = 1ms) - * @see getZeroMotionDetectionDuration() - * @see MPU9150_RA_ZRMOT_DUR - */ -void MPU9150::setZeroMotionDetectionDuration(uint8_t duration) { - I2Cdev::writeByte(devAddr, MPU9150_RA_ZRMOT_DUR, duration); -} - -// FIFO_EN register - -/** Get temperature FIFO enabled value. - * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and - * 66) to be written into the FIFO buffer. - * @return Current temperature FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getTempFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set temperature FIFO enabled value. - * @param enabled New temperature FIFO enabled value - * @see getTempFIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setTempFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, enabled); -} -/** Get gyroscope X-axis FIFO enabled value. - * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and - * 68) to be written into the FIFO buffer. - * @return Current gyroscope X-axis FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getXGyroFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set gyroscope X-axis FIFO enabled value. - * @param enabled New gyroscope X-axis FIFO enabled value - * @see getXGyroFIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setXGyroFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, enabled); -} -/** Get gyroscope Y-axis FIFO enabled value. - * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and - * 70) to be written into the FIFO buffer. - * @return Current gyroscope Y-axis FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getYGyroFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set gyroscope Y-axis FIFO enabled value. - * @param enabled New gyroscope Y-axis FIFO enabled value - * @see getYGyroFIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setYGyroFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, enabled); -} -/** Get gyroscope Z-axis FIFO enabled value. - * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and - * 72) to be written into the FIFO buffer. - * @return Current gyroscope Z-axis FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getZGyroFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set gyroscope Z-axis FIFO enabled value. - * @param enabled New gyroscope Z-axis FIFO enabled value - * @see getZGyroFIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setZGyroFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, enabled); -} -/** Get accelerometer FIFO enabled value. - * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, - * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be - * written into the FIFO buffer. - * @return Current accelerometer FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getAccelFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set accelerometer FIFO enabled value. - * @param enabled New accelerometer FIFO enabled value - * @see getAccelFIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setAccelFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, enabled); -} -/** Get Slave 2 FIFO enabled value. - * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) - * associated with Slave 2 to be written into the FIFO buffer. - * @return Current Slave 2 FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getSlave2FIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set Slave 2 FIFO enabled value. - * @param enabled New Slave 2 FIFO enabled value - * @see getSlave2FIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setSlave2FIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, enabled); -} -/** Get Slave 1 FIFO enabled value. - * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) - * associated with Slave 1 to be written into the FIFO buffer. - * @return Current Slave 1 FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getSlave1FIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set Slave 1 FIFO enabled value. - * @param enabled New Slave 1 FIFO enabled value - * @see getSlave1FIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setSlave1FIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, enabled); -} -/** Get Slave 0 FIFO enabled value. - * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) - * associated with Slave 0 to be written into the FIFO buffer. - * @return Current Slave 0 FIFO enabled value - * @see MPU9150_RA_FIFO_EN - */ -bool MPU9150::getSlave0FIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV0_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set Slave 0 FIFO enabled value. - * @param enabled New Slave 0 FIFO enabled value - * @see getSlave0FIFOEnabled() - * @see MPU9150_RA_FIFO_EN - */ -void MPU9150::setSlave0FIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV0_FIFO_EN_BIT, enabled); -} - -// I2C_MST_CTRL register - -/** Get multi-master enabled value. - * Multi-master capability allows multiple I2C masters to operate on the same - * bus. In circuits where multi-master capability is required, set MULT_MST_EN - * to 1. This will increase current drawn by approximately 30uA. - * - * In circuits where multi-master capability is required, the state of the I2C - * bus must always be monitored by each separate I2C Master. Before an I2C - * Master can assume arbitration of the bus, it must first confirm that no other - * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the - * MPU-60X0's bus arbitration detection logic is turned on, enabling it to - * detect when the bus is available. - * - * @return Current multi-master enabled value - * @see MPU9150_RA_I2C_MST_CTRL - */ -bool MPU9150::getMultiMasterEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_MULT_MST_EN_BIT, buffer); - return buffer[0]; -} -/** Set multi-master enabled value. - * @param enabled New multi-master enabled value - * @see getMultiMasterEnabled() - * @see MPU9150_RA_I2C_MST_CTRL - */ -void MPU9150::setMultiMasterEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_MULT_MST_EN_BIT, enabled); -} -/** Get wait-for-external-sensor-data enabled value. - * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be - * delayed until External Sensor data from the Slave Devices are loaded into the - * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor - * data (i.e. from gyro and accel) and external sensor data have been loaded to - * their respective data registers (i.e. the data is synced) when the Data Ready - * interrupt is triggered. - * - * @return Current wait-for-external-sensor-data enabled value - * @see MPU9150_RA_I2C_MST_CTRL - */ -bool MPU9150::getWaitForExternalSensorEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, buffer); - return buffer[0]; -} -/** Set wait-for-external-sensor-data enabled value. - * @param enabled New wait-for-external-sensor-data enabled value - * @see getWaitForExternalSensorEnabled() - * @see MPU9150_RA_I2C_MST_CTRL - */ -void MPU9150::setWaitForExternalSensorEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, enabled); -} -/** Get Slave 3 FIFO enabled value. - * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) - * associated with Slave 3 to be written into the FIFO buffer. - * @return Current Slave 3 FIFO enabled value - * @see MPU9150_RA_MST_CTRL - */ -bool MPU9150::getSlave3FIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_SLV_3_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set Slave 3 FIFO enabled value. - * @param enabled New Slave 3 FIFO enabled value - * @see getSlave3FIFOEnabled() - * @see MPU9150_RA_MST_CTRL - */ -void MPU9150::setSlave3FIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_SLV_3_FIFO_EN_BIT, enabled); -} -/** Get slave read/write transition enabled value. - * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave - * read to the next slave read. If the bit equals 0, there will be a restart - * between reads. If the bit equals 1, there will be a stop followed by a start - * of the following read. When a write transaction follows a read transaction, - * the stop followed by a start of the successive write will be always used. - * - * @return Current slave read/write transition enabled value - * @see MPU9150_RA_I2C_MST_CTRL - */ -bool MPU9150::getSlaveReadWriteTransitionEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_P_NSR_BIT, buffer); - return buffer[0]; -} -/** Set slave read/write transition enabled value. - * @param enabled New slave read/write transition enabled value - * @see getSlaveReadWriteTransitionEnabled() - * @see MPU9150_RA_I2C_MST_CTRL - */ -void MPU9150::setSlaveReadWriteTransitionEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_P_NSR_BIT, enabled); -} -/** Get I2C master clock speed. - * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the - * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to - * the following table: - * - *
- * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
- * ------------+------------------------+-------------------
- * 0           | 348kHz                 | 23
- * 1           | 333kHz                 | 24
- * 2           | 320kHz                 | 25
- * 3           | 308kHz                 | 26
- * 4           | 296kHz                 | 27
- * 5           | 286kHz                 | 28
- * 6           | 276kHz                 | 29
- * 7           | 267kHz                 | 30
- * 8           | 258kHz                 | 31
- * 9           | 500kHz                 | 16
- * 10          | 471kHz                 | 17
- * 11          | 444kHz                 | 18
- * 12          | 421kHz                 | 19
- * 13          | 400kHz                 | 20
- * 14          | 381kHz                 | 21
- * 15          | 364kHz                 | 22
- * 
- * - * @return Current I2C master clock speed - * @see MPU9150_RA_I2C_MST_CTRL - */ -uint8_t MPU9150::getMasterClockSpeed() { - I2Cdev::readBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_I2C_MST_CLK_LENGTH, buffer); - return buffer[0]; -} -/** Set I2C master clock speed. - * @reparam speed Current I2C master clock speed - * @see MPU9150_RA_I2C_MST_CTRL - */ -void MPU9150::setMasterClockSpeed(uint8_t speed) { - I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_I2C_MST_CLK_LENGTH, speed); -} - -// I2C_SLV* registers (Slave 0-3) - -/** Get the I2C address of the specified slave (0-3). - * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read - * operation, and if it is cleared, then it's a write operation. The remaining - * bits (6-0) are the 7-bit device address of the slave device. - * - * In read mode, the result of the read is placed in the lowest available - * EXT_SENS_DATA register. For further information regarding the allocation of - * read results, please refer to the EXT_SENS_DATA register description - * (Registers 73 - 96). - * - * The MPU-9150 supports a total of five slaves, but Slave 4 has unique - * characteristics, and so it has its own functions (getSlave4* and setSlave4*). - * - * I2C data transactions are performed at the Sample Rate, as defined in - * Register 25. The user is responsible for ensuring that I2C data transactions - * to and from each enabled Slave can be completed within a single period of the - * Sample Rate. - * - * The I2C slave access rate can be reduced relative to the Sample Rate. This - * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a - * slave's access rate is reduced relative to the Sample Rate is determined by - * I2C_MST_DELAY_CTRL (Register 103). - * - * The processing order for the slaves is fixed. The sequence followed for - * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a - * particular Slave is disabled it will be skipped. - * - * Each slave can either be accessed at the sample rate or at a reduced sample - * rate. In a case where some slaves are accessed at the Sample Rate and some - * slaves are accessed at the reduced rate, the sequence of accessing the slaves - * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will - * be skipped if their access rate dictates that they should not be accessed - * during that particular cycle. For further information regarding the reduced - * access rate, please refer to Register 52. Whether a slave is accessed at the - * Sample Rate or at the reduced rate is determined by the Delay Enable bits in - * Register 103. - * - * @param num Slave number (0-3) - * @return Current address for specified slave - * @see MPU9150_RA_I2C_SLV0_ADDR - */ -uint8_t MPU9150::getSlaveAddress(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_ADDR + num*3, buffer); - return buffer[0]; -} -/** Set the I2C address of the specified slave (0-3). - * @param num Slave number (0-3) - * @param address New address for specified slave - * @see getSlaveAddress() - * @see MPU9150_RA_I2C_SLV0_ADDR - */ -void MPU9150::setSlaveAddress(uint8_t num, uint8_t address) { - if (num > 3) return; - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_ADDR + num*3, address); -} -/** Get the active internal register for the specified slave (0-3). - * Read/write operations for this slave will be done to whatever internal - * register address is stored in this MPU register. - * - * The MPU-9150 supports a total of five slaves, but Slave 4 has unique - * characteristics, and so it has its own functions. - * - * @param num Slave number (0-3) - * @return Current active register for specified slave - * @see MPU9150_RA_I2C_SLV0_REG - */ -uint8_t MPU9150::getSlaveRegister(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_REG + num*3, buffer); - return buffer[0]; -} -/** Set the active internal register for the specified slave (0-3). - * @param num Slave number (0-3) - * @param reg New active register for specified slave - * @see getSlaveRegister() - * @see MPU9150_RA_I2C_SLV0_REG - */ -void MPU9150::setSlaveRegister(uint8_t num, uint8_t reg) { - if (num > 3) return; - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_REG + num*3, reg); -} -/** Get the enabled value for the specified slave (0-3). - * When set to 1, this bit enables Slave 0 for data transfer operations. When - * cleared to 0, this bit disables Slave 0 from data transfer operations. - * @param num Slave number (0-3) - * @return Current enabled value for specified slave - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -bool MPU9150::getSlaveEnabled(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_EN_BIT, buffer); - return buffer[0]; -} -/** Set the enabled value for the specified slave (0-3). - * @param num Slave number (0-3) - * @param enabled New enabled value for specified slave - * @see getSlaveEnabled() - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -void MPU9150::setSlaveEnabled(uint8_t num, bool enabled) { - if (num > 3) return; - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_EN_BIT, enabled); -} -/** Get word pair byte-swapping enabled for the specified slave (0-3). - * When set to 1, this bit enables byte swapping. When byte swapping is enabled, - * the high and low bytes of a word pair are swapped. Please refer to - * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0, - * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA - * registers in the order they were transferred. - * - * @param num Slave number (0-3) - * @return Current word pair byte-swapping enabled value for specified slave - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -bool MPU9150::getSlaveWordByteSwap(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_BYTE_SW_BIT, buffer); - return buffer[0]; -} -/** Set word pair byte-swapping enabled for the specified slave (0-3). - * @param num Slave number (0-3) - * @param enabled New word pair byte-swapping enabled value for specified slave - * @see getSlaveWordByteSwap() - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -void MPU9150::setSlaveWordByteSwap(uint8_t num, bool enabled) { - if (num > 3) return; - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_BYTE_SW_BIT, enabled); -} -/** Get write mode for the specified slave (0-3). - * When set to 1, the transaction will read or write data only. When cleared to - * 0, the transaction will write a register address prior to reading or writing - * data. This should equal 0 when specifying the register address within the - * Slave device to/from which the ensuing data transaction will take place. - * - * @param num Slave number (0-3) - * @return Current write mode for specified slave (0 = register address + data, 1 = data only) - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -bool MPU9150::getSlaveWriteMode(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_REG_DIS_BIT, buffer); - return buffer[0]; -} -/** Set write mode for the specified slave (0-3). - * @param num Slave number (0-3) - * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) - * @see getSlaveWriteMode() - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -void MPU9150::setSlaveWriteMode(uint8_t num, bool mode) { - if (num > 3) return; - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_REG_DIS_BIT, mode); -} -/** Get word pair grouping order offset for the specified slave (0-3). - * This sets specifies the grouping order of word pairs received from registers. - * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even, - * then odd register addresses) are paired to form a word. When set to 1, bytes - * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even - * register addresses) are paired to form a word. - * - * @param num Slave number (0-3) - * @return Current word pair grouping order offset for specified slave - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -bool MPU9150::getSlaveWordGroupOffset(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_GRP_BIT, buffer); - return buffer[0]; -} -/** Set word pair grouping order offset for the specified slave (0-3). - * @param num Slave number (0-3) - * @param enabled New word pair grouping order offset for specified slave - * @see getSlaveWordGroupOffset() - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -void MPU9150::setSlaveWordGroupOffset(uint8_t num, bool enabled) { - if (num > 3) return; - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_GRP_BIT, enabled); -} -/** Get number of bytes to read for the specified slave (0-3). - * Specifies the number of bytes transferred to and from Slave 0. Clearing this - * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN. - * @param num Slave number (0-3) - * @return Number of bytes to read for specified slave - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -uint8_t MPU9150::getSlaveDataLength(uint8_t num) { - if (num > 3) return 0; - I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_I2C_SLV_LEN_LENGTH, buffer); - return buffer[0]; -} -/** Set number of bytes to read for the specified slave (0-3). - * @param num Slave number (0-3) - * @param length Number of bytes to read for specified slave - * @see getSlaveDataLength() - * @see MPU9150_RA_I2C_SLV0_CTRL - */ -void MPU9150::setSlaveDataLength(uint8_t num, uint8_t length) { - if (num > 3) return; - I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_I2C_SLV_LEN_LENGTH, length); -} - -// I2C_SLV* registers (Slave 4) - -/** Get the I2C address of Slave 4. - * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read - * operation, and if it is cleared, then it's a write operation. The remaining - * bits (6-0) are the 7-bit device address of the slave device. - * - * @return Current address for Slave 4 - * @see getSlaveAddress() - * @see MPU9150_RA_I2C_SLV4_ADDR - */ -uint8_t MPU9150::getSlave4Address() { - I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_ADDR, buffer); - return buffer[0]; -} -/** Set the I2C address of Slave 4. - * @param address New address for Slave 4 - * @see getSlave4Address() - * @see MPU9150_RA_I2C_SLV4_ADDR - */ -void MPU9150::setSlave4Address(uint8_t address) { - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_ADDR, address); -} -/** Get the active internal register for the Slave 4. - * Read/write operations for this slave will be done to whatever internal - * register address is stored in this MPU register. - * - * @return Current active register for Slave 4 - * @see MPU9150_RA_I2C_SLV4_REG - */ -uint8_t MPU9150::getSlave4Register() { - I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_REG, buffer); - return buffer[0]; -} -/** Set the active internal register for Slave 4. - * @param reg New active register for Slave 4 - * @see getSlave4Register() - * @see MPU9150_RA_I2C_SLV4_REG - */ -void MPU9150::setSlave4Register(uint8_t reg) { - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_REG, reg); -} -/** Set new byte to write to Slave 4. - * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW - * is set 1 (set to read), this register has no effect. - * @param data New byte to write to Slave 4 - * @see MPU9150_RA_I2C_SLV4_DO - */ -void MPU9150::setSlave4OutputByte(uint8_t data) { - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_DO, data); -} -/** Get the enabled value for the Slave 4. - * When set to 1, this bit enables Slave 4 for data transfer operations. When - * cleared to 0, this bit disables Slave 4 from data transfer operations. - * @return Current enabled value for Slave 4 - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -bool MPU9150::getSlave4Enabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_EN_BIT, buffer); - return buffer[0]; -} -/** Set the enabled value for Slave 4. - * @param enabled New enabled value for Slave 4 - * @see getSlave4Enabled() - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -void MPU9150::setSlave4Enabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_EN_BIT, enabled); -} -/** Get the enabled value for Slave 4 transaction interrupts. - * When set to 1, this bit enables the generation of an interrupt signal upon - * completion of a Slave 4 transaction. When cleared to 0, this bit disables the - * generation of an interrupt signal upon completion of a Slave 4 transaction. - * The interrupt status can be observed in Register 54. - * - * @return Current enabled value for Slave 4 transaction interrupts. - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -bool MPU9150::getSlave4InterruptEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_INT_EN_BIT, buffer); - return buffer[0]; -} -/** Set the enabled value for Slave 4 transaction interrupts. - * @param enabled New enabled value for Slave 4 transaction interrupts. - * @see getSlave4InterruptEnabled() - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -void MPU9150::setSlave4InterruptEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_INT_EN_BIT, enabled); -} -/** Get write mode for Slave 4. - * When set to 1, the transaction will read or write data only. When cleared to - * 0, the transaction will write a register address prior to reading or writing - * data. This should equal 0 when specifying the register address within the - * Slave device to/from which the ensuing data transaction will take place. - * - * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only) - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -bool MPU9150::getSlave4WriteMode() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_REG_DIS_BIT, buffer); - return buffer[0]; -} -/** Set write mode for the Slave 4. - * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) - * @see getSlave4WriteMode() - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -void MPU9150::setSlave4WriteMode(bool mode) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_REG_DIS_BIT, mode); -} -/** Get Slave 4 master delay value. - * This configures the reduced access rate of I2C slaves relative to the Sample - * Rate. When a slave's access rate is decreased relative to the Sample Rate, - * the slave is accessed every: - * - * 1 / (1 + I2C_MST_DLY) samples - * - * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and - * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to - * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For - * further information regarding the Sample Rate, please refer to register 25. - * - * @return Current Slave 4 master delay value - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -uint8_t MPU9150::getSlave4MasterDelay() { - I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_I2C_SLV4_MST_DLY_LENGTH, buffer); - return buffer[0]; -} -/** Set Slave 4 master delay value. - * @param delay New Slave 4 master delay value - * @see getSlave4MasterDelay() - * @see MPU9150_RA_I2C_SLV4_CTRL - */ -void MPU9150::setSlave4MasterDelay(uint8_t delay) { - I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_I2C_SLV4_MST_DLY_LENGTH, delay); -} -/** Get last available byte read from Slave 4. - * This register stores the data read from Slave 4. This field is populated - * after a read transaction. - * @return Last available byte read from to Slave 4 - * @see MPU9150_RA_I2C_SLV4_DI - */ -uint8_t MPU9150::getSlate4InputByte() { - I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_DI, buffer); - return buffer[0]; -} - -// I2C_MST_STATUS register - -/** Get FSYNC interrupt status. - * This bit reflects the status of the FSYNC interrupt from an external device - * into the MPU-60X0. This is used as a way to pass an external interrupt - * through the MPU-60X0 to the host application processor. When set to 1, this - * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG - * (Register 55). - * @return FSYNC interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getPassthroughStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_PASS_THROUGH_BIT, buffer); - return buffer[0]; -} -/** Get Slave 4 transaction done status. - * Automatically sets to 1 when a Slave 4 transaction has completed. This - * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register - * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the - * I2C_SLV4_CTRL register (Register 52). - * @return Slave 4 transaction done status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave4IsDone() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_DONE_BIT, buffer); - return buffer[0]; -} -/** Get master arbitration lost status. - * This bit automatically sets to 1 when the I2C Master has lost arbitration of - * the auxiliary I2C bus (an error condition). This triggers an interrupt if the - * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. - * @return Master arbitration lost status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getLostArbitration() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_LOST_ARB_BIT, buffer); - return buffer[0]; -} -/** Get Slave 4 NACK status. - * This bit automatically sets to 1 when the I2C Master receives a NACK in a - * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN - * bit in the INT_ENABLE register (Register 56) is asserted. - * @return Slave 4 NACK interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave4Nack() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_NACK_BIT, buffer); - return buffer[0]; -} -/** Get Slave 3 NACK status. - * This bit automatically sets to 1 when the I2C Master receives a NACK in a - * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN - * bit in the INT_ENABLE register (Register 56) is asserted. - * @return Slave 3 NACK interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave3Nack() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV3_NACK_BIT, buffer); - return buffer[0]; -} -/** Get Slave 2 NACK status. - * This bit automatically sets to 1 when the I2C Master receives a NACK in a - * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN - * bit in the INT_ENABLE register (Register 56) is asserted. - * @return Slave 2 NACK interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave2Nack() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV2_NACK_BIT, buffer); - return buffer[0]; -} -/** Get Slave 1 NACK status. - * This bit automatically sets to 1 when the I2C Master receives a NACK in a - * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN - * bit in the INT_ENABLE register (Register 56) is asserted. - * @return Slave 1 NACK interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave1Nack() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV1_NACK_BIT, buffer); - return buffer[0]; -} -/** Get Slave 0 NACK status. - * This bit automatically sets to 1 when the I2C Master receives a NACK in a - * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN - * bit in the INT_ENABLE register (Register 56) is asserted. - * @return Slave 0 NACK interrupt status - * @see MPU9150_RA_I2C_MST_STATUS - */ -bool MPU9150::getSlave0Nack() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV0_NACK_BIT, buffer); - return buffer[0]; -} - -// INT_PIN_CFG register - -/** Get interrupt logic level mode. - * Will be set 0 for active-high, 1 for active-low. - * @return Current interrupt mode (0=active-high, 1=active-low) - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_LEVEL_BIT - */ -bool MPU9150::getInterruptMode() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_LEVEL_BIT, buffer); - return buffer[0]; -} -/** Set interrupt logic level mode. - * @param mode New interrupt mode (0=active-high, 1=active-low) - * @see getInterruptMode() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_LEVEL_BIT - */ -void MPU9150::setInterruptMode(bool mode) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_LEVEL_BIT, mode); -} -/** Get interrupt drive mode. - * Will be set 0 for push-pull, 1 for open-drain. - * @return Current interrupt drive mode (0=push-pull, 1=open-drain) - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_OPEN_BIT - */ -bool MPU9150::getInterruptDrive() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_OPEN_BIT, buffer); - return buffer[0]; -} -/** Set interrupt drive mode. - * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) - * @see getInterruptDrive() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_OPEN_BIT - */ -void MPU9150::setInterruptDrive(bool drive) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_OPEN_BIT, drive); -} -/** Get interrupt latch mode. - * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared. - * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared) - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_LATCH_INT_EN_BIT - */ -bool MPU9150::getInterruptLatch() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_LATCH_INT_EN_BIT, buffer); - return buffer[0]; -} -/** Set interrupt latch mode. - * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) - * @see getInterruptLatch() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_LATCH_INT_EN_BIT - */ -void MPU9150::setInterruptLatch(bool latch) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_LATCH_INT_EN_BIT, latch); -} -/** Get interrupt latch clear mode. - * Will be set 0 for status-read-only, 1 for any-register-read. - * @return Current latch clear mode (0=status-read-only, 1=any-register-read) - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT - */ -bool MPU9150::getInterruptLatchClear() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_RD_CLEAR_BIT, buffer); - return buffer[0]; -} -/** Set interrupt latch clear mode. - * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) - * @see getInterruptLatchClear() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT - */ -void MPU9150::setInterruptLatchClear(bool clear) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_RD_CLEAR_BIT, clear); -} -/** Get FSYNC interrupt logic level mode. - * @return Current FSYNC interrupt mode (0=active-high, 1=active-low) - * @see getFSyncInterruptMode() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT - */ -bool MPU9150::getFSyncInterruptLevel() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); - return buffer[0]; -} -/** Set FSYNC interrupt logic level mode. - * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) - * @see getFSyncInterruptMode() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT - */ -void MPU9150::setFSyncInterruptLevel(bool level) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT, level); -} -/** Get FSYNC pin interrupt enabled setting. - * Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled setting - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT - */ -bool MPU9150::getFSyncInterruptEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_EN_BIT, buffer); - return buffer[0]; -} -/** Set FSYNC pin interrupt enabled setting. - * @param enabled New FSYNC pin interrupt enabled setting - * @see getFSyncInterruptEnabled() - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT - */ -void MPU9150::setFSyncInterruptEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_EN_BIT, enabled); -} -/** Get I2C bypass enabled status. - * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to - * 0, the host application processor will be able to directly access the - * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host - * application processor will not be able to directly access the auxiliary I2C - * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 - * bit[5]). - * @return Current I2C bypass enabled status - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT - */ -bool MPU9150::getI2CBypassEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_I2C_BYPASS_EN_BIT, buffer); - return buffer[0]; -} -/** Set I2C bypass enabled status. - * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to - * 0, the host application processor will be able to directly access the - * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host - * application processor will not be able to directly access the auxiliary I2C - * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 - * bit[5]). - * @param enabled New I2C bypass enabled status - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT - */ -void MPU9150::setI2CBypassEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_I2C_BYPASS_EN_BIT, enabled); -} -/** Get reference clock output enabled status. - * When this bit is equal to 1, a reference clock output is provided at the - * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For - * further information regarding CLKOUT, please refer to the MPU-60X0 Product - * Specification document. - * @return Current reference clock output enabled status - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_CLKOUT_EN_BIT - */ -bool MPU9150::getClockOutputEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_CLKOUT_EN_BIT, buffer); - return buffer[0]; -} -/** Set reference clock output enabled status. - * When this bit is equal to 1, a reference clock output is provided at the - * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For - * further information regarding CLKOUT, please refer to the MPU-60X0 Product - * Specification document. - * @param enabled New reference clock output enabled status - * @see MPU9150_RA_INT_PIN_CFG - * @see MPU9150_INTCFG_CLKOUT_EN_BIT - */ -void MPU9150::setClockOutputEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_CLKOUT_EN_BIT, enabled); -} - -// INT_ENABLE register - -/** Get full interrupt enabled status. - * Full register byte for all interrupts, for quick reading. Each bit will be - * set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FF_BIT - **/ -uint8_t MPU9150::getIntEnabled() { - I2Cdev::readByte(devAddr, MPU9150_RA_INT_ENABLE, buffer); - return buffer[0]; -} -/** Set full interrupt enabled status. - * Full register byte for all interrupts, for quick reading. Each bit should be - * set 0 for disabled, 1 for enabled. - * @param enabled New interrupt enabled status - * @see getIntFreefallEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FF_BIT - **/ -void MPU9150::setIntEnabled(uint8_t enabled) { - I2Cdev::writeByte(devAddr, MPU9150_RA_INT_ENABLE, enabled); -} -/** Get Free Fall interrupt enabled status. - * Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FF_BIT - **/ -bool MPU9150::getIntFreefallEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FF_BIT, buffer); - return buffer[0]; -} -/** Set Free Fall interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntFreefallEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FF_BIT - **/ -void MPU9150::setIntFreefallEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FF_BIT, enabled); -} -/** Get Motion Detection interrupt enabled status. - * Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_MOT_BIT - **/ -bool MPU9150::getIntMotionEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_MOT_BIT, buffer); - return buffer[0]; -} -/** Set Motion Detection interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntMotionEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_MOT_BIT - **/ -void MPU9150::setIntMotionEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_MOT_BIT, enabled); -} -/** Get Zero Motion Detection interrupt enabled status. - * Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_ZMOT_BIT - **/ -bool MPU9150::getIntZeroMotionEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_ZMOT_BIT, buffer); - return buffer[0]; -} -/** Set Zero Motion Detection interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntZeroMotionEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_ZMOT_BIT - **/ -void MPU9150::setIntZeroMotionEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_ZMOT_BIT, enabled); -} -/** Get FIFO Buffer Overflow interrupt enabled status. - * Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT - **/ -bool MPU9150::getIntFIFOBufferOverflowEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); - return buffer[0]; -} -/** Set FIFO Buffer Overflow interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntFIFOBufferOverflowEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT - **/ -void MPU9150::setIntFIFOBufferOverflowEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, enabled); -} -/** Get I2C Master interrupt enabled status. - * This enables any of the I2C Master interrupt sources to generate an - * interrupt. Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT - **/ -bool MPU9150::getIntI2CMasterEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); - return buffer[0]; -} -/** Set I2C Master interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntI2CMasterEnabled() - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT - **/ -void MPU9150::setIntI2CMasterEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_I2C_MST_INT_BIT, enabled); -} -/** Get Data Ready interrupt enabled setting. - * This event occurs each time a write operation to all of the sensor registers - * has been completed. Will be set 0 for disabled, 1 for enabled. - * @return Current interrupt enabled status - * @see MPU9150_RA_INT_ENABLE - * @see MPU9150_INTERRUPT_DATA_RDY_BIT - */ -bool MPU9150::getIntDataReadyEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); - return buffer[0]; -} -/** Set Data Ready interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntDataReadyEnabled() - * @see MPU9150_RA_INT_CFG - * @see MPU9150_INTERRUPT_DATA_RDY_BIT - */ -void MPU9150::setIntDataReadyEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DATA_RDY_BIT, enabled); -} - -// INT_STATUS register - -/** Get full set of interrupt status bits. - * These bits clear to 0 after the register has been read. Very useful - * for getting multiple INT statuses, since each single bit read clears - * all of them because it has to read the whole byte. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - */ -uint8_t MPU9150::getIntStatus() { - I2Cdev::readByte(devAddr, MPU9150_RA_INT_STATUS, buffer); - return buffer[0]; -} -/** Get Free Fall interrupt status. - * This bit automatically sets to 1 when a Free Fall interrupt has been - * generated. The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_FF_BIT - */ -bool MPU9150::getIntFreefallStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FF_BIT, buffer); - return buffer[0]; -} -/** Get Motion Detection interrupt status. - * This bit automatically sets to 1 when a Motion Detection interrupt has been - * generated. The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_MOT_BIT - */ -bool MPU9150::getIntMotionStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_MOT_BIT, buffer); - return buffer[0]; -} -/** Get Zero Motion Detection interrupt status. - * This bit automatically sets to 1 when a Zero Motion Detection interrupt has - * been generated. The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_ZMOT_BIT - */ -bool MPU9150::getIntZeroMotionStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_ZMOT_BIT, buffer); - return buffer[0]; -} -/** Get FIFO Buffer Overflow interrupt status. - * This bit automatically sets to 1 when a Free Fall interrupt has been - * generated. The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT - */ -bool MPU9150::getIntFIFOBufferOverflowStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); - return buffer[0]; -} -/** Get I2C Master interrupt status. - * This bit automatically sets to 1 when an I2C Master interrupt has been - * generated. For a list of I2C Master interrupts, please refer to Register 54. - * The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT - */ -bool MPU9150::getIntI2CMasterStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); - return buffer[0]; -} -/** Get Data Ready interrupt status. - * This bit automatically sets to 1 when a Data Ready interrupt has been - * generated. The bit clears to 0 after the register has been read. - * @return Current interrupt status - * @see MPU9150_RA_INT_STATUS - * @see MPU9150_INTERRUPT_DATA_RDY_BIT - */ -bool MPU9150::getIntDataReadyStatus() { - I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); - return buffer[0]; -} - -// ACCEL_*OUT_* registers - -/** Get raw 9-axis motion sensor readings (accel/gyro/compass). - * FUNCTION NOT FULLY IMPLEMENTED YET. - * @param ax 16-bit signed integer container for accelerometer X-axis value - * @param ay 16-bit signed integer container for accelerometer Y-axis value - * @param az 16-bit signed integer container for accelerometer Z-axis value - * @param gx 16-bit signed integer container for gyroscope X-axis value - * @param gy 16-bit signed integer container for gyroscope Y-axis value - * @param gz 16-bit signed integer container for gyroscope Z-axis value - * @param mx 16-bit signed integer container for magnetometer X-axis value - * @param my 16-bit signed integer container for magnetometer Y-axis value - * @param mz 16-bit signed integer container for magnetometer Z-axis value - * @see getMotion6() - * @see getAcceleration() - * @see getRotation() - * @see MPU9150_RA_ACCEL_XOUT_H - */ -void MPU9150::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz) { - - //get accel and gyro - getMotion6(ax, ay, az, gx, gy, gz); - - //read mag - I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer - delay(10); - I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer - delay(10); - I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); - *mx = (((int16_t)buffer[0]) << 8) | buffer[1]; - *my = (((int16_t)buffer[2]) << 8) | buffer[3]; - *mz = (((int16_t)buffer[4]) << 8) | buffer[5]; -} -/** Get raw 6-axis motion sensor readings (accel/gyro). - * Retrieves all currently available motion sensor values. - * @param ax 16-bit signed integer container for accelerometer X-axis value - * @param ay 16-bit signed integer container for accelerometer Y-axis value - * @param az 16-bit signed integer container for accelerometer Z-axis value - * @param gx 16-bit signed integer container for gyroscope X-axis value - * @param gy 16-bit signed integer container for gyroscope Y-axis value - * @param gz 16-bit signed integer container for gyroscope Z-axis value - * @see getAcceleration() - * @see getRotation() - * @see MPU9150_RA_ACCEL_XOUT_H - */ -void MPU9150::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { - I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 14, buffer); - *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; - *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; - *az = (((int16_t)buffer[4]) << 8) | buffer[5]; - *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; - *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; - *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; -} -/** Get 3-axis accelerometer readings. - * These registers store the most recent accelerometer measurements. - * Accelerometer measurements are written to these registers at the Sample Rate - * as defined in Register 25. - * - * The accelerometer measurement registers, along with the temperature - * measurement registers, gyroscope measurement registers, and external sensor - * data registers, are composed of two sets of registers: an internal register - * set and a user-facing read register set. - * - * The data within the accelerometer sensors' internal register set is always - * updated at the Sample Rate. Meanwhile, the user-facing read register set - * duplicates the internal register set's data values whenever the serial - * interface is idle. This guarantees that a burst read of sensor registers will - * read measurements from the same sampling instant. Note that if burst reads - * are not used, the user is responsible for ensuring a set of single byte reads - * correspond to a single sampling instant by checking the Data Ready interrupt. - * - * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS - * (Register 28). For each full scale setting, the accelerometers' sensitivity - * per LSB in ACCEL_xOUT is shown in the table below: - * - *
- * AFS_SEL | Full Scale Range | LSB Sensitivity
- * --------+------------------+----------------
- * 0       | +/- 2g           | 8192 LSB/mg
- * 1       | +/- 4g           | 4096 LSB/mg
- * 2       | +/- 8g           | 2048 LSB/mg
- * 3       | +/- 16g          | 1024 LSB/mg
- * 
- * - * @param x 16-bit signed integer container for X-axis acceleration - * @param y 16-bit signed integer container for Y-axis acceleration - * @param z 16-bit signed integer container for Z-axis acceleration - * @see MPU9150_RA_GYRO_XOUT_H - */ -void MPU9150::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { - I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 6, buffer); - *x = (((int16_t)buffer[0]) << 8) | buffer[1]; - *y = (((int16_t)buffer[2]) << 8) | buffer[3]; - *z = (((int16_t)buffer[4]) << 8) | buffer[5]; -} -/** Get X-axis accelerometer reading. - * @return X-axis acceleration measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_ACCEL_XOUT_H - */ -int16_t MPU9150::getAccelerationX() { - I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} -/** Get Y-axis accelerometer reading. - * @return Y-axis acceleration measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_ACCEL_YOUT_H - */ -int16_t MPU9150::getAccelerationY() { - I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_YOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} -/** Get Z-axis accelerometer reading. - * @return Z-axis acceleration measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_ACCEL_ZOUT_H - */ -int16_t MPU9150::getAccelerationZ() { - I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_ZOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} - -// TEMP_OUT_* registers - -/** Get current internal temperature. - * @return Temperature reading in 16-bit 2's complement format - * @see MPU9150_RA_TEMP_OUT_H - */ -int16_t MPU9150::getTemperature() { - I2Cdev::readBytes(devAddr, MPU9150_RA_TEMP_OUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} - -void MPU9150::getHeading(int16_t* mx, int16_t* my, int16_t* mz) { - //read mag - I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer - delay(10); - I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer - delay(10); - I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); - *mx = (((int16_t)buffer[0]) << 8) | buffer[1]; - *my = (((int16_t)buffer[2]) << 8) | buffer[3]; - *mz = (((int16_t)buffer[4]) << 8) | buffer[5]; -} -// GYRO_*OUT_* registers - -/** Get 3-axis gyroscope readings. - * These gyroscope measurement registers, along with the accelerometer - * measurement registers, temperature measurement registers, and external sensor - * data registers, are composed of two sets of registers: an internal register - * set and a user-facing read register set. - * The data within the gyroscope sensors' internal register set is always - * updated at the Sample Rate. Meanwhile, the user-facing read register set - * duplicates the internal register set's data values whenever the serial - * interface is idle. This guarantees that a burst read of sensor registers will - * read measurements from the same sampling instant. Note that if burst reads - * are not used, the user is responsible for ensuring a set of single byte reads - * correspond to a single sampling instant by checking the Data Ready interrupt. - * - * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL - * (Register 27). For each full scale setting, the gyroscopes' sensitivity per - * LSB in GYRO_xOUT is shown in the table below: - * - *
- * FS_SEL | Full Scale Range   | LSB Sensitivity
- * -------+--------------------+----------------
- * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
- * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
- * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
- * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
- * 
- * - * @param x 16-bit signed integer container for X-axis rotation - * @param y 16-bit signed integer container for Y-axis rotation - * @param z 16-bit signed integer container for Z-axis rotation - * @see getMotion6() - * @see MPU9150_RA_GYRO_XOUT_H - */ -void MPU9150::getRotation(int16_t* x, int16_t* y, int16_t* z) { - I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 6, buffer); - *x = (((int16_t)buffer[0]) << 8) | buffer[1]; - *y = (((int16_t)buffer[2]) << 8) | buffer[3]; - *z = (((int16_t)buffer[4]) << 8) | buffer[5]; -} -/** Get X-axis gyroscope reading. - * @return X-axis rotation measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_GYRO_XOUT_H - */ -int16_t MPU9150::getRotationX() { - I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} -/** Get Y-axis gyroscope reading. - * @return Y-axis rotation measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_GYRO_YOUT_H - */ -int16_t MPU9150::getRotationY() { - I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_YOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} -/** Get Z-axis gyroscope reading. - * @return Z-axis rotation measurement in 16-bit 2's complement format - * @see getMotion6() - * @see MPU9150_RA_GYRO_ZOUT_H - */ -int16_t MPU9150::getRotationZ() { - I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_ZOUT_H, 2, buffer); - return (((int16_t)buffer[0]) << 8) | buffer[1]; -} - -// EXT_SENS_DATA_* registers - -/** Read single byte from external sensor data register. - * These registers store data read from external sensors by the Slave 0, 1, 2, - * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in - * I2C_SLV4_DI (Register 53). - * - * External sensor data is written to these registers at the Sample Rate as - * defined in Register 25. This access rate can be reduced by using the Slave - * Delay Enable registers (Register 103). - * - * External sensor data registers, along with the gyroscope measurement - * registers, accelerometer measurement registers, and temperature measurement - * registers, are composed of two sets of registers: an internal register set - * and a user-facing read register set. - * - * The data within the external sensors' internal register set is always updated - * at the Sample Rate (or the reduced access rate) whenever the serial interface - * is idle. This guarantees that a burst read of sensor registers will read - * measurements from the same sampling instant. Note that if burst reads are not - * used, the user is responsible for ensuring a set of single byte reads - * correspond to a single sampling instant by checking the Data Ready interrupt. - * - * Data is placed in these external sensor data registers according to - * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, - * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from - * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as - * defined in Register 25) or delayed rate (if specified in Register 52 and - * 103). During each Sample cycle, slave reads are performed in order of Slave - * number. If all slaves are enabled with more than zero bytes to be read, the - * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. - * - * Each enabled slave will have EXT_SENS_DATA registers associated with it by - * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from - * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may - * change the higher numbered slaves' associated registers. Furthermore, if - * fewer total bytes are being read from the external sensors as a result of - * such a change, then the data remaining in the registers which no longer have - * an associated slave device (i.e. high numbered registers) will remain in - * these previously allocated registers unless reset. - * - * If the sum of the read lengths of all SLVx transactions exceed the number of - * available EXT_SENS_DATA registers, the excess bytes will be dropped. There - * are 24 EXT_SENS_DATA registers and hence the total read lengths between all - * the slaves cannot be greater than 24 or some bytes will be lost. - * - * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further - * information regarding the characteristics of Slave 4, please refer to - * Registers 49 to 53. - * - * EXAMPLE: - * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and - * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that - * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 - * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 - * will be associated with Slave 1. If Slave 2 is enabled as well, registers - * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. - * - * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then - * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 - * instead. - * - * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: - * If a slave is disabled at any time, the space initially allocated to the - * slave in the EXT_SENS_DATA register, will remain associated with that slave. - * This is to avoid dynamic adjustment of the register allocation. - * - * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all - * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). - * - * This above is also true if one of the slaves gets NACKed and stops - * functioning. - * - * @param position Starting position (0-23) - * @return Byte read from register - */ -uint8_t MPU9150::getExternalSensorByte(int position) { - I2Cdev::readByte(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, buffer); - return buffer[0]; -} -/** Read word (2 bytes) from external sensor data registers. - * @param position Starting position (0-21) - * @return Word read from register - * @see getExternalSensorByte() - */ -uint16_t MPU9150::getExternalSensorWord(int position) { - I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 2, buffer); - return (((uint16_t)buffer[0]) << 8) | buffer[1]; -} -/** Read double word (4 bytes) from external sensor data registers. - * @param position Starting position (0-20) - * @return Double word read from registers - * @see getExternalSensorByte() - */ -uint32_t MPU9150::getExternalSensorDWord(int position) { - I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 4, buffer); - return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; -} - -// MOT_DETECT_STATUS register - -/** Get X-axis negative motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_XNEG_BIT - */ -bool MPU9150::getXNegMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XNEG_BIT, buffer); - return buffer[0]; -} -/** Get X-axis positive motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_XPOS_BIT - */ -bool MPU9150::getXPosMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XPOS_BIT, buffer); - return buffer[0]; -} -/** Get Y-axis negative motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_YNEG_BIT - */ -bool MPU9150::getYNegMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YNEG_BIT, buffer); - return buffer[0]; -} -/** Get Y-axis positive motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_YPOS_BIT - */ -bool MPU9150::getYPosMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YPOS_BIT, buffer); - return buffer[0]; -} -/** Get Z-axis negative motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_ZNEG_BIT - */ -bool MPU9150::getZNegMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZNEG_BIT, buffer); - return buffer[0]; -} -/** Get Z-axis positive motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_ZPOS_BIT - */ -bool MPU9150::getZPosMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZPOS_BIT, buffer); - return buffer[0]; -} -/** Get zero motion detection interrupt status. - * @return Motion detection status - * @see MPU9150_RA_MOT_DETECT_STATUS - * @see MPU9150_MOTION_MOT_ZRMOT_BIT - */ -bool MPU9150::getZeroMotionDetected() { - I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZRMOT_BIT, buffer); - return buffer[0]; -} - -// I2C_SLV*_DO register - -/** Write byte to Data Output container for specified slave. - * This register holds the output data written into Slave when Slave is set to - * write mode. For further information regarding Slave control, please - * refer to Registers 37 to 39 and immediately following. - * @param num Slave number (0-3) - * @param data Byte to write - * @see MPU9150_RA_I2C_SLV0_DO - */ -void MPU9150::setSlaveOutputByte(uint8_t num, uint8_t data) { - if (num > 3) return; - I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_DO + num, data); -} - -// I2C_MST_DELAY_CTRL register - -/** Get external data shadow delay enabled status. - * This register is used to specify the timing of external sensor data - * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external - * sensor data is delayed until all data has been received. - * @return Current external data shadow delay enabled status. - * @see MPU9150_RA_I2C_MST_DELAY_CTRL - * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT - */ -bool MPU9150::getExternalShadowDelayEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); - return buffer[0]; -} -/** Set external data shadow delay enabled status. - * @param enabled New external data shadow delay enabled status. - * @see getExternalShadowDelayEnabled() - * @see MPU9150_RA_I2C_MST_DELAY_CTRL - * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT - */ -void MPU9150::setExternalShadowDelayEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled); -} -/** Get slave delay enabled status. - * When a particular slave delay is enabled, the rate of access for the that - * slave device is reduced. When a slave's access rate is decreased relative to - * the Sample Rate, the slave is accessed every: - * - * 1 / (1 + I2C_MST_DLY) Samples - * - * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25) - * and DLPF_CFG (register 26). - * - * For further information regarding I2C_MST_DLY, please refer to register 52. - * For further information regarding the Sample Rate, please refer to register 25. - * - * @param num Slave number (0-4) - * @return Current slave delay enabled status. - * @see MPU9150_RA_I2C_MST_DELAY_CTRL - * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT - */ -bool MPU9150::getSlaveDelayEnabled(uint8_t num) { - // MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. - if (num > 4) return 0; - I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, num, buffer); - return buffer[0]; -} -/** Set slave delay enabled status. - * @param num Slave number (0-4) - * @param enabled New slave delay enabled status. - * @see MPU9150_RA_I2C_MST_DELAY_CTRL - * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT - */ -void MPU9150::setSlaveDelayEnabled(uint8_t num, bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, num, enabled); -} - -// SIGNAL_PATH_RESET register - -/** Reset gyroscope signal path. - * The reset will revert the signal path analog to digital converters and - * filters to their power up configurations. - * @see MPU9150_RA_SIGNAL_PATH_RESET - * @see MPU9150_PATHRESET_GYRO_RESET_BIT - */ -void MPU9150::resetGyroscopePath() { - I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_GYRO_RESET_BIT, true); -} -/** Reset accelerometer signal path. - * The reset will revert the signal path analog to digital converters and - * filters to their power up configurations. - * @see MPU9150_RA_SIGNAL_PATH_RESET - * @see MPU9150_PATHRESET_ACCEL_RESET_BIT - */ -void MPU9150::resetAccelerometerPath() { - I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_ACCEL_RESET_BIT, true); -} -/** Reset temperature sensor signal path. - * The reset will revert the signal path analog to digital converters and - * filters to their power up configurations. - * @see MPU9150_RA_SIGNAL_PATH_RESET - * @see MPU9150_PATHRESET_TEMP_RESET_BIT - */ -void MPU9150::resetTemperaturePath() { - I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_TEMP_RESET_BIT, true); -} - -// MOT_DETECT_CTRL register - -/** Get accelerometer power-on delay. - * The accelerometer data path provides samples to the sensor registers, Motion - * detection, Zero Motion detection, and Free Fall detection modules. The - * signal path contains filters which must be flushed on wake-up with new - * samples before the detection modules begin operations. The default wake-up - * delay, of 4ms can be lengthened by up to 3ms. This additional delay is - * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select - * any value above zero unless instructed otherwise by InvenSense. Please refer - * to Section 8 of the MPU-6000/MPU-9150 Product Specification document for - * further information regarding the detection modules. - * @return Current accelerometer power-on delay - * @see MPU9150_RA_MOT_DETECT_CTRL - * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT - */ -uint8_t MPU9150::getAccelerometerPowerOnDelay() { - I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); - return buffer[0]; -} -/** Set accelerometer power-on delay. - * @param delay New accelerometer power-on delay (0-3) - * @see getAccelerometerPowerOnDelay() - * @see MPU9150_RA_MOT_DETECT_CTRL - * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT - */ -void MPU9150::setAccelerometerPowerOnDelay(uint8_t delay) { - I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH, delay); -} -/** Get Free Fall detection counter decrement configuration. - * Detection is registered by the Free Fall detection module after accelerometer - * measurements meet their respective threshold conditions over a specified - * number of samples. When the threshold conditions are met, the corresponding - * detection counter increments by 1. The user may control the rate at which the - * detection counter decrements when the threshold condition is not met by - * configuring FF_COUNT. The decrement rate can be set according to the - * following table: - * - *
- * FF_COUNT | Counter Decrement
- * ---------+------------------
- * 0        | Reset
- * 1        | 1
- * 2        | 2
- * 3        | 4
- * 
- * - * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will - * reset the counter to 0. For further information on Free Fall detection, - * please refer to Registers 29 to 32. - * - * @return Current decrement configuration - * @see MPU9150_RA_MOT_DETECT_CTRL - * @see MPU9150_DETECT_FF_COUNT_BIT - */ -uint8_t MPU9150::getFreefallDetectionCounterDecrement() { - I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_DETECT_FF_COUNT_LENGTH, buffer); - return buffer[0]; -} -/** Set Free Fall detection counter decrement configuration. - * @param decrement New decrement configuration value - * @see getFreefallDetectionCounterDecrement() - * @see MPU9150_RA_MOT_DETECT_CTRL - * @see MPU9150_DETECT_FF_COUNT_BIT - */ -void MPU9150::setFreefallDetectionCounterDecrement(uint8_t decrement) { - I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_DETECT_FF_COUNT_LENGTH, decrement); -} -/** Get Motion detection counter decrement configuration. - * Detection is registered by the Motion detection module after accelerometer - * measurements meet their respective threshold conditions over a specified - * number of samples. When the threshold conditions are met, the corresponding - * detection counter increments by 1. The user may control the rate at which the - * detection counter decrements when the threshold condition is not met by - * configuring MOT_COUNT. The decrement rate can be set according to the - * following table: - * - *
- * MOT_COUNT | Counter Decrement
- * ----------+------------------
- * 0         | Reset
- * 1         | 1
- * 2         | 2
- * 3         | 4
- * 
- * - * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will - * reset the counter to 0. For further information on Motion detection, - * please refer to Registers 29 to 32. - * - */ -uint8_t MPU9150::getMotionDetectionCounterDecrement() { - I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, buffer); - return buffer[0]; -} -/** Set Motion detection counter decrement configuration. - * @param decrement New decrement configuration value - * @see getMotionDetectionCounterDecrement() - * @see MPU9150_RA_MOT_DETECT_CTRL - * @see MPU9150_DETECT_MOT_COUNT_BIT - */ -void MPU9150::setMotionDetectionCounterDecrement(uint8_t decrement) { - I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, decrement); -} - -// USER_CTRL register - -/** Get FIFO enabled status. - * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer - * cannot be written to or read from while disabled. The FIFO buffer's state - * does not change unless the MPU-60X0 is power cycled. - * @return Current FIFO enabled status - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_FIFO_EN_BIT - */ -bool MPU9150::getFIFOEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_EN_BIT, buffer); - return buffer[0]; -} -/** Set FIFO enabled status. - * @param enabled New FIFO enabled status - * @see getFIFOEnabled() - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_FIFO_EN_BIT - */ -void MPU9150::setFIFOEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_EN_BIT, enabled); -} -/** Get I2C Master Mode enabled status. - * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the - * external sensor slave devices on the auxiliary I2C bus. When this bit is - * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically - * driven by the primary I2C bus (SDA and SCL). This is a precondition to - * enabling Bypass Mode. For further information regarding Bypass Mode, please - * refer to Register 55. - * @return Current I2C Master Mode enabled status - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_I2C_MST_EN_BIT - */ -bool MPU9150::getI2CMasterModeEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_EN_BIT, buffer); - return buffer[0]; -} -/** Set I2C Master Mode enabled status. - * @param enabled New I2C Master Mode enabled status - * @see getI2CMasterModeEnabled() - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_I2C_MST_EN_BIT - */ -void MPU9150::setI2CMasterModeEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_EN_BIT, enabled); -} -/** Switch from I2C to SPI mode (MPU-6000 only) - * If this is set, the primary SPI interface will be enabled in place of the - * disabled primary I2C interface. - */ -void MPU9150::switchSPIEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_IF_DIS_BIT, enabled); -} -/** Reset the FIFO. - * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This - * bit automatically clears to 0 after the reset has been triggered. - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_FIFO_RESET_BIT - */ -void MPU9150::resetFIFO() { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_RESET_BIT, true); -} -/** Reset the I2C Master. - * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0. - * This bit automatically clears to 0 after the reset has been triggered. - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_I2C_MST_RESET_BIT - */ -void MPU9150::resetI2CMaster() { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_RESET_BIT, true); -} -/** Reset all sensor registers and signal paths. - * When set to 1, this bit resets the signal paths for all sensors (gyroscopes, - * accelerometers, and temperature sensor). This operation will also clear the - * sensor registers. This bit automatically clears to 0 after the reset has been - * triggered. - * - * When resetting only the signal path (and not the sensor registers), please - * use Register 104, SIGNAL_PATH_RESET. - * - * @see MPU9150_RA_USER_CTRL - * @see MPU9150_USERCTRL_SIG_COND_RESET_BIT - */ -void MPU9150::resetSensors() { - I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_SIG_COND_RESET_BIT, true); -} - -// PWR_MGMT_1 register - -/** Trigger a full device reset. - * A small delay of ~50ms may be desirable after triggering a reset. - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_DEVICE_RESET_BIT - */ -void MPU9150::reset() { - I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_DEVICE_RESET_BIT, true); -} -/** Get sleep mode status. - * Setting the SLEEP bit in the register puts the device into very low power - * sleep mode. In this mode, only the serial interface and internal registers - * remain active, allowing for a very low standby current. Clearing this bit - * puts the device back into normal mode. To save power, the individual standby - * selections for each of the gyros should be used if any gyro axis is not used - * by the application. - * @return Current sleep mode enabled status - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_SLEEP_BIT - */ -bool MPU9150::getSleepEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_SLEEP_BIT, buffer); - return buffer[0]; -} -/** Set sleep mode status. - * @param enabled New sleep mode enabled status - * @see getSleepEnabled() - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_SLEEP_BIT - */ -void MPU9150::setSleepEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_SLEEP_BIT, enabled); -} -/** Get wake cycle enabled status. - * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle - * between sleep mode and waking up to take a single sample of data from active - * sensors at a rate determined by LP_WAKE_CTRL (register 108). - * @return Current sleep mode enabled status - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_CYCLE_BIT - */ -bool MPU9150::getWakeCycleEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CYCLE_BIT, buffer); - return buffer[0]; -} -/** Set wake cycle enabled status. - * @param enabled New sleep mode enabled status - * @see getWakeCycleEnabled() - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_CYCLE_BIT - */ -void MPU9150::setWakeCycleEnabled(bool enabled) { - I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CYCLE_BIT, enabled); -} -/** Get temperature sensor enabled status. - * Control the usage of the internal temperature sensor. - * - * Note: this register stores the *disabled* value, but for consistency with the - * rest of the code, the function is named and used with standard true/false - * values to indicate whether the sensor is enabled or disabled, respectively. - * - * @return Current temperature sensor enabled status - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_TEMP_DIS_BIT - */ -bool MPU9150::getTempSensorEnabled() { - I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, buffer); - return buffer[0] == 0; // 1 is actually disabled here -} -/** Set temperature sensor enabled status. - * Note: this register stores the *disabled* value, but for consistency with the - * rest of the code, the function is named and used with standard true/false - * values to indicate whether the sensor is enabled or disabled, respectively. - * - * @param enabled New temperature sensor enabled status - * @see getTempSensorEnabled() - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_TEMP_DIS_BIT - */ -void MPU9150::setTempSensorEnabled(bool enabled) { - // 1 is actually disabled here - I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, !enabled); -} -/** Get clock source setting. - * @return Current clock source setting - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_CLKSEL_BIT - * @see MPU9150_PWR1_CLKSEL_LENGTH - */ -uint8_t MPU9150::getClockSource() { - I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_PWR1_CLKSEL_LENGTH, buffer); - return buffer[0]; -} -/** Set clock source setting. - * An internal 8MHz oscillator, gyroscope based clock, or external sources can - * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator - * or an external source is chosen as the clock source, the MPU-60X0 can operate - * in low power modes with the gyroscopes disabled. - * - * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. - * However, it is highly recommended that the device be configured to use one of - * the gyroscopes (or an external clock source) as the clock reference for - * improved stability. The clock source can be selected according to the following table: - * - *
- * CLK_SEL | Clock Source
- * --------+--------------------------------------
- * 0       | Internal oscillator
- * 1       | PLL with X Gyro reference
- * 2       | PLL with Y Gyro reference
- * 3       | PLL with Z Gyro reference
- * 4       | PLL with external 32.768kHz reference
- * 5       | PLL with external 19.2MHz reference
- * 6       | Reserved
- * 7       | Stops the clock and keeps the timing generator in reset
- * 
- * - * @param source New clock source setting - * @see getClockSource() - * @see MPU9150_RA_PWR_MGMT_1 - * @see MPU9150_PWR1_CLKSEL_BIT - * @see MPU9150_PWR1_CLKSEL_LENGTH - */ -void MPU9150::setClockSource(uint8_t source) { - I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_PWR1_CLKSEL_LENGTH, source); -} - -// PWR_MGMT_2 register - -/** Get wake frequency in Accel-Only Low Power Mode. - * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting - * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode, - * the device will power off all devices except for the primary I2C interface, - * waking only the accelerometer at fixed intervals to take a single - * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL - * as shown below: - * - *
- * LP_WAKE_CTRL | Wake-up Frequency
- * -------------+------------------
- * 0            | 1.25 Hz
- * 1            | 2.5 Hz
- * 2            | 5 Hz
- * 3            | 10 Hz
- * 
- *
- * For further information regarding the MPU-60X0's power modes, please refer to
- * Register 107.
- *
- * @return Current wake frequency
- * @see MPU9150_RA_PWR_MGMT_2
- */
-uint8_t MPU9150::getWakeFrequency() {
-    I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
-    return buffer[0];
-}
-/** Set wake frequency in Accel-Only Low Power Mode.
- * @param frequency New wake frequency
- * @see MPU9150_RA_PWR_MGMT_2
- */
-void MPU9150::setWakeFrequency(uint8_t frequency) {
-    I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
-}
-
-/** Get X-axis accelerometer standby enabled status.
- * If enabled, the X-axis will not gather or report data (or use power).
- * @return Current X-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_XA_BIT
- */
-bool MPU9150::getStandbyXAccelEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XA_BIT, buffer);
-    return buffer[0];
-}
-/** Set X-axis accelerometer standby enabled status.
- * @param New X-axis standby enabled status
- * @see getStandbyXAccelEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_XA_BIT
- */
-void MPU9150::setStandbyXAccelEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XA_BIT, enabled);
-}
-/** Get Y-axis accelerometer standby enabled status.
- * If enabled, the Y-axis will not gather or report data (or use power).
- * @return Current Y-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_YA_BIT
- */
-bool MPU9150::getStandbyYAccelEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YA_BIT, buffer);
-    return buffer[0];
-}
-/** Set Y-axis accelerometer standby enabled status.
- * @param New Y-axis standby enabled status
- * @see getStandbyYAccelEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_YA_BIT
- */
-void MPU9150::setStandbyYAccelEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YA_BIT, enabled);
-}
-/** Get Z-axis accelerometer standby enabled status.
- * If enabled, the Z-axis will not gather or report data (or use power).
- * @return Current Z-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_ZA_BIT
- */
-bool MPU9150::getStandbyZAccelEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZA_BIT, buffer);
-    return buffer[0];
-}
-/** Set Z-axis accelerometer standby enabled status.
- * @param New Z-axis standby enabled status
- * @see getStandbyZAccelEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_ZA_BIT
- */
-void MPU9150::setStandbyZAccelEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZA_BIT, enabled);
-}
-/** Get X-axis gyroscope standby enabled status.
- * If enabled, the X-axis will not gather or report data (or use power).
- * @return Current X-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_XG_BIT
- */
-bool MPU9150::getStandbyXGyroEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XG_BIT, buffer);
-    return buffer[0];
-}
-/** Set X-axis gyroscope standby enabled status.
- * @param New X-axis standby enabled status
- * @see getStandbyXGyroEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_XG_BIT
- */
-void MPU9150::setStandbyXGyroEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XG_BIT, enabled);
-}
-/** Get Y-axis gyroscope standby enabled status.
- * If enabled, the Y-axis will not gather or report data (or use power).
- * @return Current Y-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_YG_BIT
- */
-bool MPU9150::getStandbyYGyroEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YG_BIT, buffer);
-    return buffer[0];
-}
-/** Set Y-axis gyroscope standby enabled status.
- * @param New Y-axis standby enabled status
- * @see getStandbyYGyroEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_YG_BIT
- */
-void MPU9150::setStandbyYGyroEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YG_BIT, enabled);
-}
-/** Get Z-axis gyroscope standby enabled status.
- * If enabled, the Z-axis will not gather or report data (or use power).
- * @return Current Z-axis standby enabled status
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_ZG_BIT
- */
-bool MPU9150::getStandbyZGyroEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, buffer);
-    return buffer[0];
-}
-/** Set Z-axis gyroscope standby enabled status.
- * @param New Z-axis standby enabled status
- * @see getStandbyZGyroEnabled()
- * @see MPU9150_RA_PWR_MGMT_2
- * @see MPU9150_PWR2_STBY_ZG_BIT
- */
-void MPU9150::setStandbyZGyroEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, enabled);
-}
-
-// FIFO_COUNT* registers
-
-/** Get current FIFO buffer size.
- * This value indicates the number of bytes stored in the FIFO buffer. This
- * number is in turn the number of bytes that can be read from the FIFO buffer
- * and it is directly proportional to the number of samples available given the
- * set of sensor data bound to be stored in the FIFO (register 35 and 36).
- * @return Current FIFO buffer size
- */
-uint16_t MPU9150::getFIFOCount() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_COUNTH, 2, buffer);
-    return (((uint16_t)buffer[0]) << 8) | buffer[1];
-}
-
-// FIFO_R_W register
-
-/** Get byte from FIFO buffer.
- * This register is used to read and write data from the FIFO buffer. Data is
- * written to the FIFO in order of register number (from lowest to highest). If
- * all the FIFO enable flags (see below) are enabled and all External Sensor
- * Data registers (Registers 73 to 96) are associated with a Slave device, the
- * contents of registers 59 through 96 will be written in order at the Sample
- * Rate.
- *
- * The contents of the sensor data registers (Registers 59 to 96) are written
- * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
- * in FIFO_EN (Register 35). An additional flag for the sensor data registers
- * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
- *
- * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
- * automatically set to 1. This bit is located in INT_STATUS (Register 58).
- * When the FIFO buffer has overflowed, the oldest data will be lost and new
- * data will be written to the FIFO.
- *
- * If the FIFO buffer is empty, reading this register will return the last byte
- * that was previously read from the FIFO until new data is available. The user
- * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
- * empty.
- *
- * @return Byte from FIFO buffer
- */
-uint8_t MPU9150::getFIFOByte() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_FIFO_R_W, buffer);
-    return buffer[0];
-}
-void MPU9150::getFIFOBytes(uint8_t *data, uint8_t length) {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_R_W, length, data);
-}
-/** Write byte to FIFO buffer.
- * @see getFIFOByte()
- * @see MPU9150_RA_FIFO_R_W
- */
-void MPU9150::setFIFOByte(uint8_t data) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_FIFO_R_W, data);
-}
-
-// WHO_AM_I register
-
-/** Get Device ID.
- * This register is used to verify the identity of the device (0b110100, 0x34).
- * @return Device ID (6 bits only! should be 0x34)
- * @see MPU9150_RA_WHO_AM_I
- * @see MPU9150_WHO_AM_I_BIT
- * @see MPU9150_WHO_AM_I_LENGTH
- */
-uint8_t MPU9150::getDeviceID() {
-    I2Cdev::readBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, buffer);
-    return buffer[0];
-}
-/** Set Device ID.
- * Write a new ID into the WHO_AM_I register (no idea why this should ever be
- * necessary though).
- * @param id New device ID to set.
- * @see getDeviceID()
- * @see MPU9150_RA_WHO_AM_I
- * @see MPU9150_WHO_AM_I_BIT
- * @see MPU9150_WHO_AM_I_LENGTH
- */
-void MPU9150::setDeviceID(uint8_t id) {
-    I2Cdev::writeBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, id);
-}
-
-// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
-
-// XG_OFFS_TC register
-
-uint8_t MPU9150::getOTPBankValid() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, buffer);
-    return buffer[0];
-}
-void MPU9150::setOTPBankValid(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, enabled);
-}
-int8_t MPU9150::getXGyroOffsetTC() {
-    I2Cdev::readBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
-    return buffer[0];
-}
-void MPU9150::setXGyroOffsetTC(int8_t offset) {
-    I2Cdev::writeBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
-}
-
-// YG_OFFS_TC register
-
-int8_t MPU9150::getYGyroOffsetTC() {
-    I2Cdev::readBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
-    return buffer[0];
-}
-void MPU9150::setYGyroOffsetTC(int8_t offset) {
-    I2Cdev::writeBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
-}
-
-// ZG_OFFS_TC register
-
-int8_t MPU9150::getZGyroOffsetTC() {
-    I2Cdev::readBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
-    return buffer[0];
-}
-void MPU9150::setZGyroOffsetTC(int8_t offset) {
-    I2Cdev::writeBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
-}
-
-// X_FINE_GAIN register
-
-int8_t MPU9150::getXFineGain() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_X_FINE_GAIN, buffer);
-    return buffer[0];
-}
-void MPU9150::setXFineGain(int8_t gain) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_X_FINE_GAIN, gain);
-}
-
-// Y_FINE_GAIN register
-
-int8_t MPU9150::getYFineGain() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_Y_FINE_GAIN, buffer);
-    return buffer[0];
-}
-void MPU9150::setYFineGain(int8_t gain) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_Y_FINE_GAIN, gain);
-}
-
-// Z_FINE_GAIN register
-
-int8_t MPU9150::getZFineGain() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_Z_FINE_GAIN, buffer);
-    return buffer[0];
-}
-void MPU9150::setZFineGain(int8_t gain) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_Z_FINE_GAIN, gain);
-}
-
-// XA_OFFS_* registers
-
-int16_t MPU9150::getXAccelOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_XA_OFFS_H, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setXAccelOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_XA_OFFS_H, offset);
-}
-
-// YA_OFFS_* register
-
-int16_t MPU9150::getYAccelOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_YA_OFFS_H, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setYAccelOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_YA_OFFS_H, offset);
-}
-
-// ZA_OFFS_* register
-
-int16_t MPU9150::getZAccelOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_ZA_OFFS_H, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setZAccelOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_ZA_OFFS_H, offset);
-}
-
-// XG_OFFS_USR* registers
-
-int16_t MPU9150::getXGyroOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_XG_OFFS_USRH, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setXGyroOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_XG_OFFS_USRH, offset);
-}
-
-// YG_OFFS_USR* register
-
-int16_t MPU9150::getYGyroOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_YG_OFFS_USRH, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setYGyroOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_YG_OFFS_USRH, offset);
-}
-
-// ZG_OFFS_USR* register
-
-int16_t MPU9150::getZGyroOffset() {
-    I2Cdev::readBytes(devAddr, MPU9150_RA_ZG_OFFS_USRH, 2, buffer);
-    return (((int16_t)buffer[0]) << 8) | buffer[1];
-}
-void MPU9150::setZGyroOffset(int16_t offset) {
-    I2Cdev::writeWord(devAddr, MPU9150_RA_ZG_OFFS_USRH, offset);
-}
-
-// INT_ENABLE register (DMP functions)
-
-bool MPU9150::getIntPLLReadyEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
-    return buffer[0];
-}
-void MPU9150::setIntPLLReadyEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, enabled);
-}
-bool MPU9150::getIntDMPEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
-    return buffer[0];
-}
-void MPU9150::setIntDMPEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, enabled);
-}
-
-// DMP_INT_STATUS
-
-bool MPU9150::getDMPInt5Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_5_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getDMPInt4Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_4_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getDMPInt3Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_3_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getDMPInt2Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_2_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getDMPInt1Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_1_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getDMPInt0Status() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_0_BIT, buffer);
-    return buffer[0];
-}
-
-// INT_STATUS register (DMP functions)
-
-bool MPU9150::getIntPLLReadyStatus() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
-    return buffer[0];
-}
-bool MPU9150::getIntDMPStatus() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
-    return buffer[0];
-}
-
-// USER_CTRL register (DMP functions)
-
-bool MPU9150::getDMPEnabled() {
-    I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, buffer);
-    return buffer[0];
-}
-void MPU9150::setDMPEnabled(bool enabled) {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, enabled);
-}
-void MPU9150::resetDMP() {
-    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_RESET_BIT, true);
-}
-
-// BANK_SEL register
-
-void MPU9150::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
-    bank &= 0x1F;
-    if (userBank) bank |= 0x20;
-    if (prefetchEnabled) bank |= 0x40;
-    I2Cdev::writeByte(devAddr, MPU9150_RA_BANK_SEL, bank);
-}
-
-// MEM_START_ADDR register
-
-void MPU9150::setMemoryStartAddress(uint8_t address) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_START_ADDR, address);
-}
-
-// MEM_R_W register
-
-uint8_t MPU9150::readMemoryByte() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_MEM_R_W, buffer);
-    return buffer[0];
-}
-void MPU9150::writeMemoryByte(uint8_t data) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_R_W, data);
-}
-void MPU9150::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
-    setMemoryBank(bank);
-    setMemoryStartAddress(address);
-    uint8_t chunkSize;
-    for (uint16_t i = 0; i < dataSize;) {
-        // determine correct chunk size according to bank position and data size
-        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
-
-        // make sure we don't go past the data size
-        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
-
-        // make sure this chunk doesn't go past the bank boundary (256 bytes)
-        if (chunkSize > 256 - address) chunkSize = 256 - address;
-
-        // read the chunk of data as specified
-        I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, data + i);
-        
-        // increase byte index by [chunkSize]
-        i += chunkSize;
-
-        // uint8_t automatically wraps to 0 at 256
-        address += chunkSize;
-
-        // if we aren't done, update bank (if necessary) and address
-        if (i < dataSize) {
-            if (address == 0) bank++;
-            setMemoryBank(bank);
-            setMemoryStartAddress(address);
-        }
-    }
-}
-bool MPU9150::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
-    setMemoryBank(bank);
-    setMemoryStartAddress(address);
-    uint8_t chunkSize;
-    uint8_t *verifyBuffer;
-    uint8_t *progBuffer;
-    uint16_t i;
-    uint8_t j;
-    if (verify) verifyBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
-    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
-    else progBuffer = NULL;
-    for (i = 0; i < dataSize;) {
-        // determine correct chunk size according to bank position and data size
-        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
-
-        // make sure we don't go past the data size
-        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
-
-        // make sure this chunk doesn't go past the bank boundary (256 bytes)
-        if (chunkSize > 256 - address) chunkSize = 256 - address;
-        
-        if (useProgMem) {
-            // write the chunk of data as specified
-            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
-        } else {
-            // write the chunk of data as specified
-            progBuffer = (uint8_t *)data + i;
-        }
-
-        I2Cdev::writeBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, progBuffer);
-
-        // verify data if needed
-        if (verify && verifyBuffer) {
-            setMemoryBank(bank);
-            setMemoryStartAddress(address);
-            I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, verifyBuffer);
-            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
-                /*Serial.print("Block write verification error, bank ");
-                Serial.print(bank, DEC);
-                Serial.print(", address ");
-                Serial.print(address, DEC);
-                Serial.print("!\nExpected:");
-                for (j = 0; j < chunkSize; j++) {
-                    Serial.print(" 0x");
-                    if (progBuffer[j] < 16) Serial.print("0");
-                    Serial.print(progBuffer[j], HEX);
-                }
-                Serial.print("\nReceived:");
-                for (uint8_t j = 0; j < chunkSize; j++) {
-                    Serial.print(" 0x");
-                    if (verifyBuffer[i + j] < 16) Serial.print("0");
-                    Serial.print(verifyBuffer[i + j], HEX);
-                }
-                Serial.print("\n");*/
-                free(verifyBuffer);
-                if (useProgMem) free(progBuffer);
-                return false; // uh oh.
-            }
-        }
-
-        // increase byte index by [chunkSize]
-        i += chunkSize;
-
-        // uint8_t automatically wraps to 0 at 256
-        address += chunkSize;
-
-        // if we aren't done, update bank (if necessary) and address
-        if (i < dataSize) {
-            if (address == 0) bank++;
-            setMemoryBank(bank);
-            setMemoryStartAddress(address);
-        }
-    }
-    if (verify) free(verifyBuffer);
-    if (useProgMem) free(progBuffer);
-    return true;
-}
-bool MPU9150::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
-    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
-}
-bool MPU9150::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
-    uint8_t *progBuffer, success, special;
-    uint16_t i, j;
-    if (useProgMem) {
-        progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
-    } else {
-        progBuffer = NULL;
-    }
-
-    // config set data is a long string of blocks with the following structure:
-    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
-    uint8_t bank, offset, length;
-    for (i = 0; i < dataSize;) {
-        if (useProgMem) {
-            bank = pgm_read_byte(data + i++);
-            offset = pgm_read_byte(data + i++);
-            length = pgm_read_byte(data + i++);
-        } else {
-            bank = data[i++];
-            offset = data[i++];
-            length = data[i++];
-        }
-
-        // write data or perform special action
-        if (length > 0) {
-            // regular block of data to write
-            /*Serial.print("Writing config block to bank ");
-            Serial.print(bank);
-            Serial.print(", offset ");
-            Serial.print(offset);
-            Serial.print(", length=");
-            Serial.println(length);*/
-            if (useProgMem) {
-                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
-                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
-            } else {
-                progBuffer = (uint8_t *)data + i;
-            }
-            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
-            i += length;
-        } else {
-            // special instruction
-            // NOTE: this kind of behavior (what and when to do certain things)
-            // is totally undocumented. This code is in here based on observed
-            // behavior only, and exactly why (or even whether) it has to be here
-            // is anybody's guess for now.
-            if (useProgMem) {
-                special = pgm_read_byte(data + i++);
-            } else {
-                special = data[i++];
-            }
-            /*Serial.print("Special command code ");
-            Serial.print(special, HEX);
-            Serial.println(" found...");*/
-            if (special == 0x01) {
-                // enable DMP-related interrupts
-                
-                //setIntZeroMotionEnabled(true);
-                //setIntFIFOBufferOverflowEnabled(true);
-                //setIntDMPEnabled(true);
-                I2Cdev::writeByte(devAddr, MPU9150_RA_INT_ENABLE, 0x32);  // single operation
-
-                success = true;
-            } else {
-                // unknown special command
-                success = false;
-            }
-        }
-        
-        if (!success) {
-            if (useProgMem) free(progBuffer);
-            return false; // uh oh
-        }
-    }
-    if (useProgMem) free(progBuffer);
-    return true;
-}
-bool MPU9150::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
-    return writeDMPConfigurationSet(data, dataSize, true);
-}
-
-// DMP_CFG_1 register
-
-uint8_t MPU9150::getDMPConfig1() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_1, buffer);
-    return buffer[0];
-}
-void MPU9150::setDMPConfig1(uint8_t config) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_1, config);
-}
-
-// DMP_CFG_2 register
-
-uint8_t MPU9150::getDMPConfig2() {
-    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_2, buffer);
-    return buffer[0];
-}
-void MPU9150::setDMPConfig2(uint8_t config) {
-    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_2, config);
-}
diff --git a/firmware/lib/imu/MPU9150.h b/firmware/lib/imu/MPU9150.h
deleted file mode 100644
index 23e8500d..00000000
--- a/firmware/lib/imu/MPU9150.h
+++ /dev/null
@@ -1,1040 +0,0 @@
-// I2Cdev library collection - MPU9150 I2C device class
-// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
-// 10/3/2011 by Jeff Rowberg 
-// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
-//
-// Changelog:
-//     ... - ongoing debug release
-
-// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
-// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
-// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
-
-/* ============================================
-I2Cdev device library code is placed under the MIT license
-Copyright (c) 2012 Jeff Rowberg
-
-Permission is hereby granted, free of charge, to any person obtaining a copy
-of this software and associated documentation files (the "Software"), to deal
-in the Software without restriction, including without limitation the rights
-to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-copies of the Software, and to permit persons to whom the Software is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in
-all copies or substantial portions of the Software.
-
-THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-THE SOFTWARE.
-===============================================
-*/
-
-#ifndef _MPU9150_H_
-#define _MPU9150_H_
-
-#include "I2Cdev.h"
-
-// Tom Carpenter's conditional PROGMEM code
-// http://forum.arduino.cc/index.php?topic=129407.0
-#ifdef __AVR__
-    #include 
-#else
-    // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
-    #ifndef __PGMSPACE_H_
-        #define __PGMSPACE_H_ 1
-        #include 
-
-        #define PROGMEM
-        #define PGM_P  const char *
-        #define PSTR(str) (str)
-        #define F(x) x
-
-        typedef void prog_void;
-        typedef char prog_char;
-        typedef unsigned char prog_uchar;
-        typedef int8_t prog_int8_t;
-        typedef uint8_t prog_uint8_t;
-        typedef int16_t prog_int16_t;
-        typedef uint16_t prog_uint16_t;
-        typedef int32_t prog_int32_t;
-        typedef uint32_t prog_uint32_t;
-
-        #define strcpy_P(dest, src) strcpy((dest), (src))
-        #define strcat_P(dest, src) strcat((dest), (src))
-        #define strcmp_P(a, b) strcmp((a), (b))
-
-        #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
-        #define pgm_read_word(addr) (*(const unsigned short *)(addr))
-        #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
-        #define pgm_read_float(addr) (*(const float *)(addr))
-
-        #define pgm_read_byte_near(addr) pgm_read_byte(addr)
-        #define pgm_read_word_near(addr) pgm_read_word(addr)
-        #define pgm_read_dword_near(addr) pgm_read_dword(addr)
-        #define pgm_read_float_near(addr) pgm_read_float(addr)
-        #define pgm_read_byte_far(addr) pgm_read_byte(addr)
-        #define pgm_read_word_far(addr) pgm_read_word(addr)
-        #define pgm_read_dword_far(addr) pgm_read_dword(addr)
-        #define pgm_read_float_far(addr) pgm_read_float(addr)
-    #endif
-#endif
-
-//Magnetometer Registers
-#define MPU9150_RA_MAG_ADDRESS		0x0C
-#define MPU9150_RA_MAG_XOUT_L		0x03
-#define MPU9150_RA_MAG_XOUT_H		0x04
-#define MPU9150_RA_MAG_YOUT_L		0x05
-#define MPU9150_RA_MAG_YOUT_H		0x06
-#define MPU9150_RA_MAG_ZOUT_L		0x07
-#define MPU9150_RA_MAG_ZOUT_H		0x08
-
-#define MPU9150_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
-#define MPU9150_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
-#define MPU9150_DEFAULT_ADDRESS     MPU9150_ADDRESS_AD0_LOW
-
-#define MPU9150_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
-#define MPU9150_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
-#define MPU9150_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
-#define MPU9150_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
-#define MPU9150_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
-#define MPU9150_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
-#define MPU9150_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
-#define MPU9150_RA_XA_OFFS_L_TC     0x07
-#define MPU9150_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
-#define MPU9150_RA_YA_OFFS_L_TC     0x09
-#define MPU9150_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
-#define MPU9150_RA_ZA_OFFS_L_TC     0x0B
-#define MPU9150_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
-#define MPU9150_RA_XG_OFFS_USRL     0x14
-#define MPU9150_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
-#define MPU9150_RA_YG_OFFS_USRL     0x16
-#define MPU9150_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
-#define MPU9150_RA_ZG_OFFS_USRL     0x18
-#define MPU9150_RA_SMPLRT_DIV       0x19
-#define MPU9150_RA_CONFIG           0x1A
-#define MPU9150_RA_GYRO_CONFIG      0x1B
-#define MPU9150_RA_ACCEL_CONFIG     0x1C
-#define MPU9150_RA_FF_THR           0x1D
-#define MPU9150_RA_FF_DUR           0x1E
-#define MPU9150_RA_MOT_THR          0x1F
-#define MPU9150_RA_MOT_DUR          0x20
-#define MPU9150_RA_ZRMOT_THR        0x21
-#define MPU9150_RA_ZRMOT_DUR        0x22
-#define MPU9150_RA_FIFO_EN          0x23
-#define MPU9150_RA_I2C_MST_CTRL     0x24
-#define MPU9150_RA_I2C_SLV0_ADDR    0x25
-#define MPU9150_RA_I2C_SLV0_REG     0x26
-#define MPU9150_RA_I2C_SLV0_CTRL    0x27
-#define MPU9150_RA_I2C_SLV1_ADDR    0x28
-#define MPU9150_RA_I2C_SLV1_REG     0x29
-#define MPU9150_RA_I2C_SLV1_CTRL    0x2A
-#define MPU9150_RA_I2C_SLV2_ADDR    0x2B
-#define MPU9150_RA_I2C_SLV2_REG     0x2C
-#define MPU9150_RA_I2C_SLV2_CTRL    0x2D
-#define MPU9150_RA_I2C_SLV3_ADDR    0x2E
-#define MPU9150_RA_I2C_SLV3_REG     0x2F
-#define MPU9150_RA_I2C_SLV3_CTRL    0x30
-#define MPU9150_RA_I2C_SLV4_ADDR    0x31
-#define MPU9150_RA_I2C_SLV4_REG     0x32
-#define MPU9150_RA_I2C_SLV4_DO      0x33
-#define MPU9150_RA_I2C_SLV4_CTRL    0x34
-#define MPU9150_RA_I2C_SLV4_DI      0x35
-#define MPU9150_RA_I2C_MST_STATUS   0x36
-#define MPU9150_RA_INT_PIN_CFG      0x37
-#define MPU9150_RA_INT_ENABLE       0x38
-#define MPU9150_RA_DMP_INT_STATUS   0x39
-#define MPU9150_RA_INT_STATUS       0x3A
-#define MPU9150_RA_ACCEL_XOUT_H     0x3B
-#define MPU9150_RA_ACCEL_XOUT_L     0x3C
-#define MPU9150_RA_ACCEL_YOUT_H     0x3D
-#define MPU9150_RA_ACCEL_YOUT_L     0x3E
-#define MPU9150_RA_ACCEL_ZOUT_H     0x3F
-#define MPU9150_RA_ACCEL_ZOUT_L     0x40
-#define MPU9150_RA_TEMP_OUT_H       0x41
-#define MPU9150_RA_TEMP_OUT_L       0x42
-#define MPU9150_RA_GYRO_XOUT_H      0x43
-#define MPU9150_RA_GYRO_XOUT_L      0x44
-#define MPU9150_RA_GYRO_YOUT_H      0x45
-#define MPU9150_RA_GYRO_YOUT_L      0x46
-#define MPU9150_RA_GYRO_ZOUT_H      0x47
-#define MPU9150_RA_GYRO_ZOUT_L      0x48
-#define MPU9150_RA_EXT_SENS_DATA_00 0x49
-#define MPU9150_RA_EXT_SENS_DATA_01 0x4A
-#define MPU9150_RA_EXT_SENS_DATA_02 0x4B
-#define MPU9150_RA_EXT_SENS_DATA_03 0x4C
-#define MPU9150_RA_EXT_SENS_DATA_04 0x4D
-#define MPU9150_RA_EXT_SENS_DATA_05 0x4E
-#define MPU9150_RA_EXT_SENS_DATA_06 0x4F
-#define MPU9150_RA_EXT_SENS_DATA_07 0x50
-#define MPU9150_RA_EXT_SENS_DATA_08 0x51
-#define MPU9150_RA_EXT_SENS_DATA_09 0x52
-#define MPU9150_RA_EXT_SENS_DATA_10 0x53
-#define MPU9150_RA_EXT_SENS_DATA_11 0x54
-#define MPU9150_RA_EXT_SENS_DATA_12 0x55
-#define MPU9150_RA_EXT_SENS_DATA_13 0x56
-#define MPU9150_RA_EXT_SENS_DATA_14 0x57
-#define MPU9150_RA_EXT_SENS_DATA_15 0x58
-#define MPU9150_RA_EXT_SENS_DATA_16 0x59
-#define MPU9150_RA_EXT_SENS_DATA_17 0x5A
-#define MPU9150_RA_EXT_SENS_DATA_18 0x5B
-#define MPU9150_RA_EXT_SENS_DATA_19 0x5C
-#define MPU9150_RA_EXT_SENS_DATA_20 0x5D
-#define MPU9150_RA_EXT_SENS_DATA_21 0x5E
-#define MPU9150_RA_EXT_SENS_DATA_22 0x5F
-#define MPU9150_RA_EXT_SENS_DATA_23 0x60
-#define MPU9150_RA_MOT_DETECT_STATUS    0x61
-#define MPU9150_RA_I2C_SLV0_DO      0x63
-#define MPU9150_RA_I2C_SLV1_DO      0x64
-#define MPU9150_RA_I2C_SLV2_DO      0x65
-#define MPU9150_RA_I2C_SLV3_DO      0x66
-#define MPU9150_RA_I2C_MST_DELAY_CTRL   0x67
-#define MPU9150_RA_SIGNAL_PATH_RESET    0x68
-#define MPU9150_RA_MOT_DETECT_CTRL      0x69
-#define MPU9150_RA_USER_CTRL        0x6A
-#define MPU9150_RA_PWR_MGMT_1       0x6B
-#define MPU9150_RA_PWR_MGMT_2       0x6C
-#define MPU9150_RA_BANK_SEL         0x6D
-#define MPU9150_RA_MEM_START_ADDR   0x6E
-#define MPU9150_RA_MEM_R_W          0x6F
-#define MPU9150_RA_DMP_CFG_1        0x70
-#define MPU9150_RA_DMP_CFG_2        0x71
-#define MPU9150_RA_FIFO_COUNTH      0x72
-#define MPU9150_RA_FIFO_COUNTL      0x73
-#define MPU9150_RA_FIFO_R_W         0x74
-#define MPU9150_RA_WHO_AM_I         0x75
-
-#define MPU9150_TC_PWR_MODE_BIT     7
-#define MPU9150_TC_OFFSET_BIT       6
-#define MPU9150_TC_OFFSET_LENGTH    6
-#define MPU9150_TC_OTP_BNK_VLD_BIT  0
-
-#define MPU9150_VDDIO_LEVEL_VLOGIC  0
-#define MPU9150_VDDIO_LEVEL_VDD     1
-
-#define MPU9150_CFG_EXT_SYNC_SET_BIT    5
-#define MPU9150_CFG_EXT_SYNC_SET_LENGTH 3
-#define MPU9150_CFG_DLPF_CFG_BIT    2
-#define MPU9150_CFG_DLPF_CFG_LENGTH 3
-
-#define MPU9150_EXT_SYNC_DISABLED       0x0
-#define MPU9150_EXT_SYNC_TEMP_OUT_L     0x1
-#define MPU9150_EXT_SYNC_GYRO_XOUT_L    0x2
-#define MPU9150_EXT_SYNC_GYRO_YOUT_L    0x3
-#define MPU9150_EXT_SYNC_GYRO_ZOUT_L    0x4
-#define MPU9150_EXT_SYNC_ACCEL_XOUT_L   0x5
-#define MPU9150_EXT_SYNC_ACCEL_YOUT_L   0x6
-#define MPU9150_EXT_SYNC_ACCEL_ZOUT_L   0x7
-
-#define MPU9150_DLPF_BW_256         0x00
-#define MPU9150_DLPF_BW_188         0x01
-#define MPU9150_DLPF_BW_98          0x02
-#define MPU9150_DLPF_BW_42          0x03
-#define MPU9150_DLPF_BW_20          0x04
-#define MPU9150_DLPF_BW_10          0x05
-#define MPU9150_DLPF_BW_5           0x06
-
-#define MPU9150_GCONFIG_FS_SEL_BIT      4
-#define MPU9150_GCONFIG_FS_SEL_LENGTH   2
-
-#define MPU9150_GYRO_FS_250         0x00
-#define MPU9150_GYRO_FS_500         0x01
-#define MPU9150_GYRO_FS_1000        0x02
-#define MPU9150_GYRO_FS_2000        0x03
-
-#define MPU9150_ACONFIG_XA_ST_BIT           7
-#define MPU9150_ACONFIG_YA_ST_BIT           6
-#define MPU9150_ACONFIG_ZA_ST_BIT           5
-#define MPU9150_ACONFIG_AFS_SEL_BIT         4
-#define MPU9150_ACONFIG_AFS_SEL_LENGTH      2
-#define MPU9150_ACONFIG_ACCEL_HPF_BIT       2
-#define MPU9150_ACONFIG_ACCEL_HPF_LENGTH    3
-
-#define MPU9150_ACCEL_FS_2          0x00
-#define MPU9150_ACCEL_FS_4          0x01
-#define MPU9150_ACCEL_FS_8          0x02
-#define MPU9150_ACCEL_FS_16         0x03
-
-#define MPU9150_DHPF_RESET          0x00
-#define MPU9150_DHPF_5              0x01
-#define MPU9150_DHPF_2P5            0x02
-#define MPU9150_DHPF_1P25           0x03
-#define MPU9150_DHPF_0P63           0x04
-#define MPU9150_DHPF_HOLD           0x07
-
-#define MPU9150_TEMP_FIFO_EN_BIT    7
-#define MPU9150_XG_FIFO_EN_BIT      6
-#define MPU9150_YG_FIFO_EN_BIT      5
-#define MPU9150_ZG_FIFO_EN_BIT      4
-#define MPU9150_ACCEL_FIFO_EN_BIT   3
-#define MPU9150_SLV2_FIFO_EN_BIT    2
-#define MPU9150_SLV1_FIFO_EN_BIT    1
-#define MPU9150_SLV0_FIFO_EN_BIT    0
-
-#define MPU9150_MULT_MST_EN_BIT     7
-#define MPU9150_WAIT_FOR_ES_BIT     6
-#define MPU9150_SLV_3_FIFO_EN_BIT   5
-#define MPU9150_I2C_MST_P_NSR_BIT   4
-#define MPU9150_I2C_MST_CLK_BIT     3
-#define MPU9150_I2C_MST_CLK_LENGTH  4
-
-#define MPU9150_CLOCK_DIV_348       0x0
-#define MPU9150_CLOCK_DIV_333       0x1
-#define MPU9150_CLOCK_DIV_320       0x2
-#define MPU9150_CLOCK_DIV_308       0x3
-#define MPU9150_CLOCK_DIV_296       0x4
-#define MPU9150_CLOCK_DIV_286       0x5
-#define MPU9150_CLOCK_DIV_276       0x6
-#define MPU9150_CLOCK_DIV_267       0x7
-#define MPU9150_CLOCK_DIV_258       0x8
-#define MPU9150_CLOCK_DIV_500       0x9
-#define MPU9150_CLOCK_DIV_471       0xA
-#define MPU9150_CLOCK_DIV_444       0xB
-#define MPU9150_CLOCK_DIV_421       0xC
-#define MPU9150_CLOCK_DIV_400       0xD
-#define MPU9150_CLOCK_DIV_381       0xE
-#define MPU9150_CLOCK_DIV_364       0xF
-
-#define MPU9150_I2C_SLV_RW_BIT      7
-#define MPU9150_I2C_SLV_ADDR_BIT    6
-#define MPU9150_I2C_SLV_ADDR_LENGTH 7
-#define MPU9150_I2C_SLV_EN_BIT      7
-#define MPU9150_I2C_SLV_BYTE_SW_BIT 6
-#define MPU9150_I2C_SLV_REG_DIS_BIT 5
-#define MPU9150_I2C_SLV_GRP_BIT     4
-#define MPU9150_I2C_SLV_LEN_BIT     3
-#define MPU9150_I2C_SLV_LEN_LENGTH  4
-
-#define MPU9150_I2C_SLV4_RW_BIT         7
-#define MPU9150_I2C_SLV4_ADDR_BIT       6
-#define MPU9150_I2C_SLV4_ADDR_LENGTH    7
-#define MPU9150_I2C_SLV4_EN_BIT         7
-#define MPU9150_I2C_SLV4_INT_EN_BIT     6
-#define MPU9150_I2C_SLV4_REG_DIS_BIT    5
-#define MPU9150_I2C_SLV4_MST_DLY_BIT    4
-#define MPU9150_I2C_SLV4_MST_DLY_LENGTH 5
-
-#define MPU9150_MST_PASS_THROUGH_BIT    7
-#define MPU9150_MST_I2C_SLV4_DONE_BIT   6
-#define MPU9150_MST_I2C_LOST_ARB_BIT    5
-#define MPU9150_MST_I2C_SLV4_NACK_BIT   4
-#define MPU9150_MST_I2C_SLV3_NACK_BIT   3
-#define MPU9150_MST_I2C_SLV2_NACK_BIT   2
-#define MPU9150_MST_I2C_SLV1_NACK_BIT   1
-#define MPU9150_MST_I2C_SLV0_NACK_BIT   0
-
-#define MPU9150_INTCFG_INT_LEVEL_BIT        7
-#define MPU9150_INTCFG_INT_OPEN_BIT         6
-#define MPU9150_INTCFG_LATCH_INT_EN_BIT     5
-#define MPU9150_INTCFG_INT_RD_CLEAR_BIT     4
-#define MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT  3
-#define MPU9150_INTCFG_FSYNC_INT_EN_BIT     2
-#define MPU9150_INTCFG_I2C_BYPASS_EN_BIT    1
-#define MPU9150_INTCFG_CLKOUT_EN_BIT        0
-
-#define MPU9150_INTMODE_ACTIVEHIGH  0x00
-#define MPU9150_INTMODE_ACTIVELOW   0x01
-
-#define MPU9150_INTDRV_PUSHPULL     0x00
-#define MPU9150_INTDRV_OPENDRAIN    0x01
-
-#define MPU9150_INTLATCH_50USPULSE  0x00
-#define MPU9150_INTLATCH_WAITCLEAR  0x01
-
-#define MPU9150_INTCLEAR_STATUSREAD 0x00
-#define MPU9150_INTCLEAR_ANYREAD    0x01
-
-#define MPU9150_INTERRUPT_FF_BIT            7
-#define MPU9150_INTERRUPT_MOT_BIT           6
-#define MPU9150_INTERRUPT_ZMOT_BIT          5
-#define MPU9150_INTERRUPT_FIFO_OFLOW_BIT    4
-#define MPU9150_INTERRUPT_I2C_MST_INT_BIT   3
-#define MPU9150_INTERRUPT_PLL_RDY_INT_BIT   2
-#define MPU9150_INTERRUPT_DMP_INT_BIT       1
-#define MPU9150_INTERRUPT_DATA_RDY_BIT      0
-
-// TODO: figure out what these actually do
-// UMPL source code is not very obivous
-#define MPU9150_DMPINT_5_BIT            5
-#define MPU9150_DMPINT_4_BIT            4
-#define MPU9150_DMPINT_3_BIT            3
-#define MPU9150_DMPINT_2_BIT            2
-#define MPU9150_DMPINT_1_BIT            1
-#define MPU9150_DMPINT_0_BIT            0
-
-#define MPU9150_MOTION_MOT_XNEG_BIT     7
-#define MPU9150_MOTION_MOT_XPOS_BIT     6
-#define MPU9150_MOTION_MOT_YNEG_BIT     5
-#define MPU9150_MOTION_MOT_YPOS_BIT     4
-#define MPU9150_MOTION_MOT_ZNEG_BIT     3
-#define MPU9150_MOTION_MOT_ZPOS_BIT     2
-#define MPU9150_MOTION_MOT_ZRMOT_BIT    0
-
-#define MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
-#define MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
-#define MPU9150_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
-#define MPU9150_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
-#define MPU9150_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
-#define MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
-
-#define MPU9150_PATHRESET_GYRO_RESET_BIT    2
-#define MPU9150_PATHRESET_ACCEL_RESET_BIT   1
-#define MPU9150_PATHRESET_TEMP_RESET_BIT    0
-
-#define MPU9150_DETECT_ACCEL_ON_DELAY_BIT       5
-#define MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH    2
-#define MPU9150_DETECT_FF_COUNT_BIT             3
-#define MPU9150_DETECT_FF_COUNT_LENGTH          2
-#define MPU9150_DETECT_MOT_COUNT_BIT            1
-#define MPU9150_DETECT_MOT_COUNT_LENGTH         2
-
-#define MPU9150_DETECT_DECREMENT_RESET  0x0
-#define MPU9150_DETECT_DECREMENT_1      0x1
-#define MPU9150_DETECT_DECREMENT_2      0x2
-#define MPU9150_DETECT_DECREMENT_4      0x3
-
-#define MPU9150_USERCTRL_DMP_EN_BIT             7
-#define MPU9150_USERCTRL_FIFO_EN_BIT            6
-#define MPU9150_USERCTRL_I2C_MST_EN_BIT         5
-#define MPU9150_USERCTRL_I2C_IF_DIS_BIT         4
-#define MPU9150_USERCTRL_DMP_RESET_BIT          3
-#define MPU9150_USERCTRL_FIFO_RESET_BIT         2
-#define MPU9150_USERCTRL_I2C_MST_RESET_BIT      1
-#define MPU9150_USERCTRL_SIG_COND_RESET_BIT     0
-
-#define MPU9150_PWR1_DEVICE_RESET_BIT   7
-#define MPU9150_PWR1_SLEEP_BIT          6
-#define MPU9150_PWR1_CYCLE_BIT          5
-#define MPU9150_PWR1_TEMP_DIS_BIT       3
-#define MPU9150_PWR1_CLKSEL_BIT         2
-#define MPU9150_PWR1_CLKSEL_LENGTH      3
-
-#define MPU9150_CLOCK_INTERNAL          0x00
-#define MPU9150_CLOCK_PLL_XGYRO         0x01
-#define MPU9150_CLOCK_PLL_YGYRO         0x02
-#define MPU9150_CLOCK_PLL_ZGYRO         0x03
-#define MPU9150_CLOCK_PLL_EXT32K        0x04
-#define MPU9150_CLOCK_PLL_EXT19M        0x05
-#define MPU9150_CLOCK_KEEP_RESET        0x07
-
-#define MPU9150_PWR2_LP_WAKE_CTRL_BIT       7
-#define MPU9150_PWR2_LP_WAKE_CTRL_LENGTH    2
-#define MPU9150_PWR2_STBY_XA_BIT            5
-#define MPU9150_PWR2_STBY_YA_BIT            4
-#define MPU9150_PWR2_STBY_ZA_BIT            3
-#define MPU9150_PWR2_STBY_XG_BIT            2
-#define MPU9150_PWR2_STBY_YG_BIT            1
-#define MPU9150_PWR2_STBY_ZG_BIT            0
-
-#define MPU9150_WAKE_FREQ_1P25      0x0
-#define MPU9150_WAKE_FREQ_2P5       0x1
-#define MPU9150_WAKE_FREQ_5         0x2
-#define MPU9150_WAKE_FREQ_10        0x3
-
-#define MPU9150_BANKSEL_PRFTCH_EN_BIT       6
-#define MPU9150_BANKSEL_CFG_USER_BANK_BIT   5
-#define MPU9150_BANKSEL_MEM_SEL_BIT         4
-#define MPU9150_BANKSEL_MEM_SEL_LENGTH      5
-
-#define MPU9150_WHO_AM_I_BIT        6
-#define MPU9150_WHO_AM_I_LENGTH     6
-
-#define MPU9150_DMP_MEMORY_BANKS        8
-#define MPU9150_DMP_MEMORY_BANK_SIZE    256
-#define MPU9150_DMP_MEMORY_CHUNK_SIZE   16
-
-// note: DMP code memory blocks defined at end of header file
-
-class MPU9150 {
-    public:
-        MPU9150();
-        MPU9150(uint8_t address);
-
-        void initialize();
-        bool testConnection();
-
-        // AUX_VDDIO register
-        uint8_t getAuxVDDIOLevel();
-        void setAuxVDDIOLevel(uint8_t level);
-
-        // SMPLRT_DIV register
-        uint8_t getRate();
-        void setRate(uint8_t rate);
-
-        // CONFIG register
-        uint8_t getExternalFrameSync();
-        void setExternalFrameSync(uint8_t sync);
-        uint8_t getDLPFMode();
-        void setDLPFMode(uint8_t bandwidth);
-
-        // GYRO_CONFIG register
-        uint8_t getFullScaleGyroRange();
-        void setFullScaleGyroRange(uint8_t range);
-
-        // ACCEL_CONFIG register
-        bool getAccelXSelfTest();
-        void setAccelXSelfTest(bool enabled);
-        bool getAccelYSelfTest();
-        void setAccelYSelfTest(bool enabled);
-        bool getAccelZSelfTest();
-        void setAccelZSelfTest(bool enabled);
-        uint8_t getFullScaleAccelRange();
-        void setFullScaleAccelRange(uint8_t range);
-        uint8_t getDHPFMode();
-        void setDHPFMode(uint8_t mode);
-
-        // FF_THR register
-        uint8_t getFreefallDetectionThreshold();
-        void setFreefallDetectionThreshold(uint8_t threshold);
-
-        // FF_DUR register
-        uint8_t getFreefallDetectionDuration();
-        void setFreefallDetectionDuration(uint8_t duration);
-
-        // MOT_THR register
-        uint8_t getMotionDetectionThreshold();
-        void setMotionDetectionThreshold(uint8_t threshold);
-
-        // MOT_DUR register
-        uint8_t getMotionDetectionDuration();
-        void setMotionDetectionDuration(uint8_t duration);
-
-        // ZRMOT_THR register
-        uint8_t getZeroMotionDetectionThreshold();
-        void setZeroMotionDetectionThreshold(uint8_t threshold);
-
-        // ZRMOT_DUR register
-        uint8_t getZeroMotionDetectionDuration();
-        void setZeroMotionDetectionDuration(uint8_t duration);
-
-        // FIFO_EN register
-        bool getTempFIFOEnabled();
-        void setTempFIFOEnabled(bool enabled);
-        bool getXGyroFIFOEnabled();
-        void setXGyroFIFOEnabled(bool enabled);
-        bool getYGyroFIFOEnabled();
-        void setYGyroFIFOEnabled(bool enabled);
-        bool getZGyroFIFOEnabled();
-        void setZGyroFIFOEnabled(bool enabled);
-        bool getAccelFIFOEnabled();
-        void setAccelFIFOEnabled(bool enabled);
-        bool getSlave2FIFOEnabled();
-        void setSlave2FIFOEnabled(bool enabled);
-        bool getSlave1FIFOEnabled();
-        void setSlave1FIFOEnabled(bool enabled);
-        bool getSlave0FIFOEnabled();
-        void setSlave0FIFOEnabled(bool enabled);
-
-        // I2C_MST_CTRL register
-        bool getMultiMasterEnabled();
-        void setMultiMasterEnabled(bool enabled);
-        bool getWaitForExternalSensorEnabled();
-        void setWaitForExternalSensorEnabled(bool enabled);
-        bool getSlave3FIFOEnabled();
-        void setSlave3FIFOEnabled(bool enabled);
-        bool getSlaveReadWriteTransitionEnabled();
-        void setSlaveReadWriteTransitionEnabled(bool enabled);
-        uint8_t getMasterClockSpeed();
-        void setMasterClockSpeed(uint8_t speed);
-
-        // I2C_SLV* registers (Slave 0-3)
-        uint8_t getSlaveAddress(uint8_t num);
-        void setSlaveAddress(uint8_t num, uint8_t address);
-        uint8_t getSlaveRegister(uint8_t num);
-        void setSlaveRegister(uint8_t num, uint8_t reg);
-        bool getSlaveEnabled(uint8_t num);
-        void setSlaveEnabled(uint8_t num, bool enabled);
-        bool getSlaveWordByteSwap(uint8_t num);
-        void setSlaveWordByteSwap(uint8_t num, bool enabled);
-        bool getSlaveWriteMode(uint8_t num);
-        void setSlaveWriteMode(uint8_t num, bool mode);
-        bool getSlaveWordGroupOffset(uint8_t num);
-        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
-        uint8_t getSlaveDataLength(uint8_t num);
-        void setSlaveDataLength(uint8_t num, uint8_t length);
-
-        // I2C_SLV* registers (Slave 4)
-        uint8_t getSlave4Address();
-        void setSlave4Address(uint8_t address);
-        uint8_t getSlave4Register();
-        void setSlave4Register(uint8_t reg);
-        void setSlave4OutputByte(uint8_t data);
-        bool getSlave4Enabled();
-        void setSlave4Enabled(bool enabled);
-        bool getSlave4InterruptEnabled();
-        void setSlave4InterruptEnabled(bool enabled);
-        bool getSlave4WriteMode();
-        void setSlave4WriteMode(bool mode);
-        uint8_t getSlave4MasterDelay();
-        void setSlave4MasterDelay(uint8_t delay);
-        uint8_t getSlate4InputByte();
-
-        // I2C_MST_STATUS register
-        bool getPassthroughStatus();
-        bool getSlave4IsDone();
-        bool getLostArbitration();
-        bool getSlave4Nack();
-        bool getSlave3Nack();
-        bool getSlave2Nack();
-        bool getSlave1Nack();
-        bool getSlave0Nack();
-
-        // INT_PIN_CFG register
-        bool getInterruptMode();
-        void setInterruptMode(bool mode);
-        bool getInterruptDrive();
-        void setInterruptDrive(bool drive);
-        bool getInterruptLatch();
-        void setInterruptLatch(bool latch);
-        bool getInterruptLatchClear();
-        void setInterruptLatchClear(bool clear);
-        bool getFSyncInterruptLevel();
-        void setFSyncInterruptLevel(bool level);
-        bool getFSyncInterruptEnabled();
-        void setFSyncInterruptEnabled(bool enabled);
-        bool getI2CBypassEnabled();
-        void setI2CBypassEnabled(bool enabled);
-        bool getClockOutputEnabled();
-        void setClockOutputEnabled(bool enabled);
-
-        // INT_ENABLE register
-        uint8_t getIntEnabled();
-        void setIntEnabled(uint8_t enabled);
-        bool getIntFreefallEnabled();
-        void setIntFreefallEnabled(bool enabled);
-        bool getIntMotionEnabled();
-        void setIntMotionEnabled(bool enabled);
-        bool getIntZeroMotionEnabled();
-        void setIntZeroMotionEnabled(bool enabled);
-        bool getIntFIFOBufferOverflowEnabled();
-        void setIntFIFOBufferOverflowEnabled(bool enabled);
-        bool getIntI2CMasterEnabled();
-        void setIntI2CMasterEnabled(bool enabled);
-        bool getIntDataReadyEnabled();
-        void setIntDataReadyEnabled(bool enabled);
-
-        // INT_STATUS register
-        uint8_t getIntStatus();
-        bool getIntFreefallStatus();
-        bool getIntMotionStatus();
-        bool getIntZeroMotionStatus();
-        bool getIntFIFOBufferOverflowStatus();
-        bool getIntI2CMasterStatus();
-        bool getIntDataReadyStatus();
-
-        // ACCEL_*OUT_* registers
-        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
-        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
-        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
-        int16_t getAccelerationX();
-        int16_t getAccelerationY();
-        int16_t getAccelerationZ();
-
-        // TEMP_OUT_* registers
-        int16_t getTemperature();
-        
-        void getHeading(int16_t* mx, int16_t* my, int16_t* mz);
-
-        // GYRO_*OUT_* registers
-        void getRotation(int16_t* x, int16_t* y, int16_t* z);
-        int16_t getRotationX();
-        int16_t getRotationY();
-        int16_t getRotationZ();
-
-        // EXT_SENS_DATA_* registers
-        uint8_t getExternalSensorByte(int position);
-        uint16_t getExternalSensorWord(int position);
-        uint32_t getExternalSensorDWord(int position);
-
-        // MOT_DETECT_STATUS register
-        bool getXNegMotionDetected();
-        bool getXPosMotionDetected();
-        bool getYNegMotionDetected();
-        bool getYPosMotionDetected();
-        bool getZNegMotionDetected();
-        bool getZPosMotionDetected();
-        bool getZeroMotionDetected();
-
-        // I2C_SLV*_DO register
-        void setSlaveOutputByte(uint8_t num, uint8_t data);
-
-        // I2C_MST_DELAY_CTRL register
-        bool getExternalShadowDelayEnabled();
-        void setExternalShadowDelayEnabled(bool enabled);
-        bool getSlaveDelayEnabled(uint8_t num);
-        void setSlaveDelayEnabled(uint8_t num, bool enabled);
-
-        // SIGNAL_PATH_RESET register
-        void resetGyroscopePath();
-        void resetAccelerometerPath();
-        void resetTemperaturePath();
-
-        // MOT_DETECT_CTRL register
-        uint8_t getAccelerometerPowerOnDelay();
-        void setAccelerometerPowerOnDelay(uint8_t delay);
-        uint8_t getFreefallDetectionCounterDecrement();
-        void setFreefallDetectionCounterDecrement(uint8_t decrement);
-        uint8_t getMotionDetectionCounterDecrement();
-        void setMotionDetectionCounterDecrement(uint8_t decrement);
-
-        // USER_CTRL register
-        bool getFIFOEnabled();
-        void setFIFOEnabled(bool enabled);
-        bool getI2CMasterModeEnabled();
-        void setI2CMasterModeEnabled(bool enabled);
-        void switchSPIEnabled(bool enabled);
-        void resetFIFO();
-        void resetI2CMaster();
-        void resetSensors();
-
-        // PWR_MGMT_1 register
-        void reset();
-        bool getSleepEnabled();
-        void setSleepEnabled(bool enabled);
-        bool getWakeCycleEnabled();
-        void setWakeCycleEnabled(bool enabled);
-        bool getTempSensorEnabled();
-        void setTempSensorEnabled(bool enabled);
-        uint8_t getClockSource();
-        void setClockSource(uint8_t source);
-
-        // PWR_MGMT_2 register
-        uint8_t getWakeFrequency();
-        void setWakeFrequency(uint8_t frequency);
-        bool getStandbyXAccelEnabled();
-        void setStandbyXAccelEnabled(bool enabled);
-        bool getStandbyYAccelEnabled();
-        void setStandbyYAccelEnabled(bool enabled);
-        bool getStandbyZAccelEnabled();
-        void setStandbyZAccelEnabled(bool enabled);
-        bool getStandbyXGyroEnabled();
-        void setStandbyXGyroEnabled(bool enabled);
-        bool getStandbyYGyroEnabled();
-        void setStandbyYGyroEnabled(bool enabled);
-        bool getStandbyZGyroEnabled();
-        void setStandbyZGyroEnabled(bool enabled);
-
-        // FIFO_COUNT_* registers
-        uint16_t getFIFOCount();
-
-        // FIFO_R_W register
-        uint8_t getFIFOByte();
-        void setFIFOByte(uint8_t data);
-        void getFIFOBytes(uint8_t *data, uint8_t length);
-
-        // WHO_AM_I register
-        uint8_t getDeviceID();
-        void setDeviceID(uint8_t id);
-        
-        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
-        
-        // XG_OFFS_TC register
-        uint8_t getOTPBankValid();
-        void setOTPBankValid(bool enabled);
-        int8_t getXGyroOffsetTC();
-        void setXGyroOffsetTC(int8_t offset);
-
-        // YG_OFFS_TC register
-        int8_t getYGyroOffsetTC();
-        void setYGyroOffsetTC(int8_t offset);
-
-        // ZG_OFFS_TC register
-        int8_t getZGyroOffsetTC();
-        void setZGyroOffsetTC(int8_t offset);
-
-        // X_FINE_GAIN register
-        int8_t getXFineGain();
-        void setXFineGain(int8_t gain);
-
-        // Y_FINE_GAIN register
-        int8_t getYFineGain();
-        void setYFineGain(int8_t gain);
-
-        // Z_FINE_GAIN register
-        int8_t getZFineGain();
-        void setZFineGain(int8_t gain);
-
-        // XA_OFFS_* registers
-        int16_t getXAccelOffset();
-        void setXAccelOffset(int16_t offset);
-
-        // YA_OFFS_* register
-        int16_t getYAccelOffset();
-        void setYAccelOffset(int16_t offset);
-
-        // ZA_OFFS_* register
-        int16_t getZAccelOffset();
-        void setZAccelOffset(int16_t offset);
-
-        // XG_OFFS_USR* registers
-        int16_t getXGyroOffset();
-        void setXGyroOffset(int16_t offset);
-
-        // YG_OFFS_USR* register
-        int16_t getYGyroOffset();
-        void setYGyroOffset(int16_t offset);
-
-        // ZG_OFFS_USR* register
-        int16_t getZGyroOffset();
-        void setZGyroOffset(int16_t offset);
-        
-        // INT_ENABLE register (DMP functions)
-        bool getIntPLLReadyEnabled();
-        void setIntPLLReadyEnabled(bool enabled);
-        bool getIntDMPEnabled();
-        void setIntDMPEnabled(bool enabled);
-        
-        // DMP_INT_STATUS
-        bool getDMPInt5Status();
-        bool getDMPInt4Status();
-        bool getDMPInt3Status();
-        bool getDMPInt2Status();
-        bool getDMPInt1Status();
-        bool getDMPInt0Status();
-
-        // INT_STATUS register (DMP functions)
-        bool getIntPLLReadyStatus();
-        bool getIntDMPStatus();
-        
-        // USER_CTRL register (DMP functions)
-        bool getDMPEnabled();
-        void setDMPEnabled(bool enabled);
-        void resetDMP();
-        
-        // BANK_SEL register
-        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
-        
-        // MEM_START_ADDR register
-        void setMemoryStartAddress(uint8_t address);
-        
-        // MEM_R_W register
-        uint8_t readMemoryByte();
-        void writeMemoryByte(uint8_t data);
-        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
-        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
-        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
-
-        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
-        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
-
-        // DMP_CFG_1 register
-        uint8_t getDMPConfig1();
-        void setDMPConfig1(uint8_t config);
-
-        // DMP_CFG_2 register
-        uint8_t getDMPConfig2();
-        void setDMPConfig2(uint8_t config);
-
-        // special methods for MotionApps 2.0 implementation
-        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS20
-            uint8_t *dmpPacketBuffer;
-            uint16_t dmpPacketSize;
-
-            uint8_t dmpInitialize();
-            bool dmpPacketAvailable();
-
-            uint8_t dmpSetFIFORate(uint8_t fifoRate);
-            uint8_t dmpGetFIFORate();
-            uint8_t dmpGetSampleStepSizeMS();
-            uint8_t dmpGetSampleFrequency();
-            int32_t dmpDecodeTemperature(int8_t tempReg);
-            
-            // Register callbacks after a packet of FIFO data is processed
-            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
-            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
-            uint8_t dmpRunFIFORateProcesses();
-            
-            // Setup FIFO for various output
-            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
-            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
-            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
-
-            // Get Fixed Point data from FIFO
-            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
-            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
-            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
-            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
-            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
-            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
-            
-            uint8_t dmpGetEuler(float *data, Quaternion *q);
-            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
-
-            // Get Floating Point data from FIFO
-            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
-
-            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
-            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
-
-            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
-
-            uint8_t dmpInitFIFOParam();
-            uint8_t dmpCloseFIFO();
-            uint8_t dmpSetGyroDataSource(uint8_t source);
-            uint8_t dmpDecodeQuantizedAccel();
-            uint32_t dmpGetGyroSumOfSquare();
-            uint32_t dmpGetAccelSumOfSquare();
-            void dmpOverrideQuaternion(long *q);
-            uint16_t dmpGetFIFOPacketSize();
-        #endif
-
-        // special methods for MotionApps 4.1 implementation
-        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS41
-            uint8_t *dmpPacketBuffer;
-            uint16_t dmpPacketSize;
-
-            uint8_t dmpInitialize();
-            bool dmpPacketAvailable();
-
-            uint8_t dmpSetFIFORate(uint8_t fifoRate);
-            uint8_t dmpGetFIFORate();
-            uint8_t dmpGetSampleStepSizeMS();
-            uint8_t dmpGetSampleFrequency();
-            int32_t dmpDecodeTemperature(int8_t tempReg);
-            
-            // Register callbacks after a packet of FIFO data is processed
-            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
-            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
-            uint8_t dmpRunFIFORateProcesses();
-            
-            // Setup FIFO for various output
-            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
-            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
-            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
-            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
-
-            // Get Fixed Point data from FIFO
-            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
-            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
-            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
-            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
-            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
-            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
-            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
-            
-            uint8_t dmpGetEuler(float *data, Quaternion *q);
-            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
-
-            // Get Floating Point data from FIFO
-            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
-            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
-
-            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
-            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
-
-            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
-
-            uint8_t dmpInitFIFOParam();
-            uint8_t dmpCloseFIFO();
-            uint8_t dmpSetGyroDataSource(uint8_t source);
-            uint8_t dmpDecodeQuantizedAccel();
-            uint32_t dmpGetGyroSumOfSquare();
-            uint32_t dmpGetAccelSumOfSquare();
-            void dmpOverrideQuaternion(long *q);
-            uint16_t dmpGetFIFOPacketSize();
-        #endif
-
-    private:
-        uint8_t devAddr;
-        uint8_t buffer[14];
-};
-
-#endif /* _MPU9150_H_ */
diff --git a/firmware/lib/imu/default_imu.h b/firmware/lib/imu/default_imu.h
index 13766500..b09b43f7 100644
--- a/firmware/lib/imu/default_imu.h
+++ b/firmware/lib/imu/default_imu.h
@@ -158,61 +158,6 @@ class MPU6050IMU: public IMUInterface
         }
 };
 
-class MPU9150IMU: public IMUInterface 
-{
-    private:
-        const float accel_scale_ = 1 / 16384.0;
-        const float gyro_scale_ = 1 / 131.0;
-
-        MPU9150 accelgyro_;
-
-        geometry_msgs__msg__Vector3 accel_;
-        geometry_msgs__msg__Vector3 gyro_;
-
-    public:
-        MPU9150IMU()
-        {
-        }
-
-        bool startSensor() override
-        {
-            Wire.begin();
-            bool ret;
-            accelgyro_.initialize();
-            ret = accelgyro_.testConnection();
-            if(!ret)
-                return false;
-
-            return true;
-        }
-
-        geometry_msgs__msg__Vector3 readAccelerometer() override
-        {
-            int16_t ax, ay, az;
-            
-            accelgyro_.getAcceleration(&ax, &ay, &az);
-
-            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
-            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
-            accel_.z = az * (double) accel_scale_ * g_to_accel_;
-
-            return accel_;
-        }
-
-        geometry_msgs__msg__Vector3 readGyroscope() override
-        {
-            int16_t gx, gy, gz;
-
-            accelgyro_.getRotation(&gx, &gy, &gz);
-
-            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
-            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
-            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
-
-            return gyro_;
-        }
-};
-
 class MPU9250IMU: public IMUInterface 
 {
     private:
diff --git a/firmware/lib/imu/imu.h b/firmware/lib/imu/imu.h
index de17bec6..3fb4728d 100644
--- a/firmware/lib/imu/imu.h
+++ b/firmware/lib/imu/imu.h
@@ -15,6 +15,10 @@
 #ifndef IMU_CONFIG_H
 #define IMU_CONFIG_H
 
+#if defined(USE_MPU9150_IMU) && !defined(USE_MPU6050_IMU)
+#define USE_MPU6050_IMU
+#endif
+
 // include the header of your new driver here similar to default_imu.h
 #include "default_imu.h"
 
@@ -28,10 +32,6 @@
     #define IMU MPU6050IMU
 #endif
 
-#ifdef USE_MPU9150_IMU
-    #define IMU MPU9150IMU
-#endif
-
 #ifdef USE_MPU9250_IMU
     #define IMU MPU9250IMU
 #endif