3 axis gyroscope & 3 axis accelerometer

Dependents:   sgam-lib sgam_mdw_NUCLEOF429ZI_impl

Fork of MPU6050 by Yihui Xiong

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU6050.cpp Source File

MPU6050.cpp

00001 //ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
00002 //written by szymon gaertig (email: szymon@gaertig.com.pl)
00003 //
00004 //Changelog:
00005 //2013-01-08 - first beta release
00006 
00007 // I2Cdev library collection - MPU6050 I2C device class
00008 // Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
00009 // 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
00010 // Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
00011 //
00012 // Changelog:
00013 //     ... - ongoing debug release
00014 
00015 // NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
00016 // DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
00017 // YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
00018 
00019 /* ============================================
00020 I2Cdev device library code is placed under the MIT license
00021 Copyright (c) 2012 Jeff Rowberg
00022 
00023 Permission is hereby granted, free of charge, to any person obtaining a copy
00024 of this software and associated documentation files (the "Software"), to deal
00025 in the Software without restriction, including without limitation the rights
00026 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00027 copies of the Software, and to permit persons to whom the Software is
00028 furnished to do so, subject to the following conditions:
00029 
00030 The above copyright notice and this permission notice shall be included in
00031 all copies or substantial portions of the Software.
00032 
00033 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00034 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00035 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00036 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00037 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00038 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00039 THE SOFTWARE.
00040 ===============================================
00041 */
00042 
00043 #include "MPU6050.h"
00044 
00045 #define LOG(args...)   // printf(args)     
00046 
00047 //instead of using pgmspace.h
00048 typedef const unsigned char prog_uchar;
00049 #define pgm_read_byte_near(x) (*(prog_uchar*)x)
00050 #define pgm_read_byte(x) (*(prog_uchar*)x)
00051 
00052 /** Specific address constructor.
00053  * @param address I2C address
00054  * @see MPU6050_DEFAULT_ADDRESS
00055  * @see MPU6050_ADDRESS_AD0_LOW
00056  * @see MPU6050_ADDRESS_AD0_HIGH
00057  */
00058 MPU6050::MPU6050(I2C &i2c, uint8_t address) : i2Cdev(i2c)
00059 {
00060     devAddr = address;
00061 }
00062 
00063 /** Power on and prepare for general usage.
00064  * This will activate the device and take it out of sleep mode (which must be done
00065  * after start-up). This function also sets both the accelerometer and the gyroscope
00066  * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
00067  * the clock source to use the X Gyro for reference, which is slightly better than
00068  * the default internal clock source.
00069  */
00070 void MPU6050::initialize()
00071 {
00072     LOG("MPU6050::initialize start\n");
00073 
00074     setClockSource(MPU6050_CLOCK_PLL_XGYRO);
00075     setFullScaleGyroRange(MPU6050_GYRO_FS_250);
00076     setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
00077     setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
00078 
00079     LOG("MPU6050::initialize end\n");
00080 }
00081 
00082 /** Verify the I2C connection.
00083  * Make sure the device is connected and responds as expected.
00084  * @return True if connection is valid, false otherwise
00085  */
00086 bool MPU6050::testConnection()
00087 {
00088     LOG("MPU6050::testConnection start\n");
00089     
00090     uint8_t deviceId = getDeviceID();
00091     
00092     LOG("DeviceId = %d\n",deviceId);
00093 
00094     return deviceId == 0x34;
00095 }
00096 
00097 // AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
00098 
00099 /** Get the auxiliary I2C supply voltage level.
00100  * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
00101  * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
00102  * the MPU-6000, which does not have a VLOGIC pin.
00103  * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
00104  */
00105 uint8_t MPU6050::getAuxVDDIOLevel()
00106 {
00107     i2Cdev.readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer);
00108     return buffer[0];
00109 }
00110 /** Set the auxiliary I2C supply voltage level.
00111  * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
00112  * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
00113  * the MPU-6000, which does not have a VLOGIC pin.
00114  * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
00115  */
00116 void MPU6050::setAuxVDDIOLevel(uint8_t level)
00117 {
00118     i2Cdev.writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level);
00119 }
00120 
00121 // SMPLRT_DIV register
00122 
00123 /** Get gyroscope output rate divider.
00124  * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
00125  * Motion detection, and Free Fall detection are all based on the Sample Rate.
00126  * The Sample Rate is generated by dividing the gyroscope output rate by
00127  * SMPLRT_DIV:
00128  *
00129  * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
00130  *
00131  * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
00132  * 7), and 1kHz when the DLPF is enabled (see Register 26).
00133  *
00134  * Note: The accelerometer output rate is 1kHz. This means that for a Sample
00135  * Rate greater than 1kHz, the same accelerometer sample may be output to the
00136  * FIFO, DMP, and sensor registers more than once.
00137  *
00138  * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
00139  * of the MPU-6000/MPU-6050 Product Specification document.
00140  *
00141  * @return Current sample rate
00142  * @see MPU6050_RA_SMPLRT_DIV
00143  */
00144 uint8_t MPU6050::getRate()
00145 {
00146     i2Cdev.readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer);
00147     return buffer[0];
00148 }
00149 /** Set gyroscope sample rate divider.
00150  * @param rate New sample rate divider
00151  * @see getRate()
00152  * @see MPU6050_RA_SMPLRT_DIV
00153  */
00154 void MPU6050::setRate(uint8_t rate)
00155 {
00156     i2Cdev.writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate);
00157 }
00158 
00159 // CONFIG register
00160 
00161 /** Get external FSYNC configuration.
00162  * Configures the external Frame Synchronization (FSYNC) pin sampling. An
00163  * external signal connected to the FSYNC pin can be sampled by configuring
00164  * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
00165  * strobes may be captured. The latched FSYNC signal will be sampled at the
00166  * Sampling Rate, as defined in register 25. After sampling, the latch will
00167  * reset to the current FSYNC signal state.
00168  *
00169  * The sampled value will be reported in place of the least significant bit in
00170  * a sensor data register determined by the value of EXT_SYNC_SET according to
00171  * the following table.
00172  *
00173  * <pre>
00174  * EXT_SYNC_SET | FSYNC Bit Location
00175  * -------------+-------------------
00176  * 0            | Input disabled
00177  * 1            | TEMP_OUT_L[0]
00178  * 2            | GYRO_XOUT_L[0]
00179  * 3            | GYRO_YOUT_L[0]
00180  * 4            | GYRO_ZOUT_L[0]
00181  * 5            | ACCEL_XOUT_L[0]
00182  * 6            | ACCEL_YOUT_L[0]
00183  * 7            | ACCEL_ZOUT_L[0]
00184  * </pre>
00185  *
00186  * @return FSYNC configuration value
00187  */
00188 uint8_t MPU6050::getExternalFrameSync()
00189 {
00190     i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer);
00191     return buffer[0];
00192 }
00193 /** Set external FSYNC configuration.
00194  * @see getExternalFrameSync()
00195  * @see MPU6050_RA_CONFIG
00196  * @param sync New FSYNC configuration value
00197  */
00198 void MPU6050::setExternalFrameSync(uint8_t sync)
00199 {
00200     i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync);
00201 }
00202 /** Get digital low-pass filter configuration.
00203  * The DLPF_CFG parameter sets the digital low pass filter configuration. It
00204  * also determines the internal sampling rate used by the device as shown in
00205  * the table below.
00206  *
00207  * Note: The accelerometer output rate is 1kHz. This means that for a Sample
00208  * Rate greater than 1kHz, the same accelerometer sample may be output to the
00209  * FIFO, DMP, and sensor registers more than once.
00210  *
00211  * <pre>
00212  *          |   ACCELEROMETER    |           GYROSCOPE
00213  * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
00214  * ---------+-----------+--------+-----------+--------+-------------
00215  * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
00216  * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
00217  * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
00218  * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
00219  * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
00220  * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
00221  * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
00222  * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
00223  * </pre>
00224  *
00225  * @return DLFP configuration
00226  * @see MPU6050_RA_CONFIG
00227  * @see MPU6050_CFG_DLPF_CFG_BIT
00228  * @see MPU6050_CFG_DLPF_CFG_LENGTH
00229  */
00230 uint8_t MPU6050::getDLPFMode()
00231 {
00232     i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer);
00233     return buffer[0];
00234 }
00235 /** Set digital low-pass filter configuration.
00236  * @param mode New DLFP configuration setting
00237  * @see getDLPFBandwidth()
00238  * @see MPU6050_DLPF_BW_256
00239  * @see MPU6050_RA_CONFIG
00240  * @see MPU6050_CFG_DLPF_CFG_BIT
00241  * @see MPU6050_CFG_DLPF_CFG_LENGTH
00242  */
00243 void MPU6050::setDLPFMode(uint8_t mode)
00244 {
00245     i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode);
00246 }
00247 
00248 // GYRO_CONFIG register
00249 
00250 /** Get full-scale gyroscope range.
00251  * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
00252  * as described in the table below.
00253  *
00254  * <pre>
00255  * 0 = +/- 250 degrees/sec
00256  * 1 = +/- 500 degrees/sec
00257  * 2 = +/- 1000 degrees/sec
00258  * 3 = +/- 2000 degrees/sec
00259  * </pre>
00260  *
00261  * @return Current full-scale gyroscope range setting
00262  * @see MPU6050_GYRO_FS_250
00263  * @see MPU6050_RA_GYRO_CONFIG
00264  * @see MPU6050_GCONFIG_FS_SEL_BIT
00265  * @see MPU6050_GCONFIG_FS_SEL_LENGTH
00266  */
00267 uint8_t MPU6050::getFullScaleGyroRange()
00268 {
00269     i2Cdev.readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer);
00270     return buffer[0];
00271 }
00272 /** Set full-scale gyroscope range.
00273  * @param range New full-scale gyroscope range value
00274  * @see getFullScaleRange()
00275  * @see MPU6050_GYRO_FS_250
00276  * @see MPU6050_RA_GYRO_CONFIG
00277  * @see MPU6050_GCONFIG_FS_SEL_BIT
00278  * @see MPU6050_GCONFIG_FS_SEL_LENGTH
00279  */
00280 void MPU6050::setFullScaleGyroRange(uint8_t range)
00281 {
00282     i2Cdev.writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range);
00283 }
00284 
00285 // ACCEL_CONFIG register
00286 
00287 /** Get self-test enabled setting for accelerometer X axis.
00288  * @return Self-test enabled value
00289  * @see MPU6050_RA_ACCEL_CONFIG
00290  */
00291 bool MPU6050::getAccelXSelfTest()
00292 {
00293     i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer);
00294     return buffer[0];
00295 }
00296 /** Get self-test enabled setting for accelerometer X axis.
00297  * @param enabled Self-test enabled value
00298  * @see MPU6050_RA_ACCEL_CONFIG
00299  */
00300 void MPU6050::setAccelXSelfTest(bool enabled)
00301 {
00302     i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled);
00303 }
00304 /** Get self-test enabled value for accelerometer Y axis.
00305  * @return Self-test enabled value
00306  * @see MPU6050_RA_ACCEL_CONFIG
00307  */
00308 bool MPU6050::getAccelYSelfTest()
00309 {
00310     i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer);
00311     return buffer[0];
00312 }
00313 /** Get self-test enabled value for accelerometer Y axis.
00314  * @param enabled Self-test enabled value
00315  * @see MPU6050_RA_ACCEL_CONFIG
00316  */
00317 void MPU6050::setAccelYSelfTest(bool enabled)
00318 {
00319     i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled);
00320 }
00321 /** Get self-test enabled value for accelerometer Z axis.
00322  * @return Self-test enabled value
00323  * @see MPU6050_RA_ACCEL_CONFIG
00324  */
00325 bool MPU6050::getAccelZSelfTest()
00326 {
00327     i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer);
00328     return buffer[0];
00329 }
00330 /** Set self-test enabled value for accelerometer Z axis.
00331  * @param enabled Self-test enabled value
00332  * @see MPU6050_RA_ACCEL_CONFIG
00333  */
00334 void MPU6050::setAccelZSelfTest(bool enabled)
00335 {
00336     i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled);
00337 }
00338 /** Get full-scale accelerometer range.
00339  * The FS_SEL parameter allows setting the full-scale range of the accelerometer
00340  * sensors, as described in the table below.
00341  *
00342  * <pre>
00343  * 0 = +/- 2g
00344  * 1 = +/- 4g
00345  * 2 = +/- 8g
00346  * 3 = +/- 16g
00347  * </pre>
00348  *
00349  * @return Current full-scale accelerometer range setting
00350  * @see MPU6050_ACCEL_FS_2
00351  * @see MPU6050_RA_ACCEL_CONFIG
00352  * @see MPU6050_ACONFIG_AFS_SEL_BIT
00353  * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
00354  */
00355 uint8_t MPU6050::getFullScaleAccelRange()
00356 {
00357     i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer);
00358     return buffer[0];
00359 }
00360 /** Set full-scale accelerometer range.
00361  * @param range New full-scale accelerometer range setting
00362  * @see getFullScaleAccelRange()
00363  */
00364 void MPU6050::setFullScaleAccelRange(uint8_t range)
00365 {
00366     i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range);
00367 }
00368 /** Get the high-pass filter configuration.
00369  * The DHPF is a filter module in the path leading to motion detectors (Free
00370  * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
00371  * available to the data registers (see Figure in Section 8 of the MPU-6000/
00372  * MPU-6050 Product Specification document).
00373  *
00374  * The high pass filter has three modes:
00375  *
00376  * <pre>
00377  *    Reset: The filter output settles to zero within one sample. This
00378  *           effectively disables the high pass filter. This mode may be toggled
00379  *           to quickly settle the filter.
00380  *
00381  *    On:    The high pass filter will pass signals above the cut off frequency.
00382  *
00383  *    Hold:  When triggered, the filter holds the present sample. The filter
00384  *           output will be the difference between the input sample and the held
00385  *           sample.
00386  * </pre>
00387  *
00388  * <pre>
00389  * ACCEL_HPF | Filter Mode | Cut-off Frequency
00390  * ----------+-------------+------------------
00391  * 0         | Reset       | None
00392  * 1         | On          | 5Hz
00393  * 2         | On          | 2.5Hz
00394  * 3         | On          | 1.25Hz
00395  * 4         | On          | 0.63Hz
00396  * 7         | Hold        | None
00397  * </pre>
00398  *
00399  * @return Current high-pass filter configuration
00400  * @see MPU6050_DHPF_RESET
00401  * @see MPU6050_RA_ACCEL_CONFIG
00402  */
00403 uint8_t MPU6050::getDHPFMode()
00404 {
00405     i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer);
00406     return buffer[0];
00407 }
00408 /** Set the high-pass filter configuration.
00409  * @param bandwidth New high-pass filter configuration
00410  * @see setDHPFMode()
00411  * @see MPU6050_DHPF_RESET
00412  * @see MPU6050_RA_ACCEL_CONFIG
00413  */
00414 void MPU6050::setDHPFMode(uint8_t bandwidth)
00415 {
00416     i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
00417 }
00418 
00419 // FF_THR register
00420 
00421 /** Get free-fall event acceleration threshold.
00422  * This register configures the detection threshold for Free Fall event
00423  * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
00424  * absolute value of the accelerometer measurements for the three axes are each
00425  * less than the detection threshold. This condition increments the Free Fall
00426  * duration counter (Register 30). The Free Fall interrupt is triggered when the
00427  * Free Fall duration counter reaches the time specified in FF_DUR.
00428  *
00429  * For more details on the Free Fall detection interrupt, see Section 8.2 of the
00430  * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
00431  * 58 of this document.
00432  *
00433  * @return Current free-fall acceleration threshold value (LSB = 2mg)
00434  * @see MPU6050_RA_FF_THR
00435  */
00436 uint8_t MPU6050::getFreefallDetectionThreshold()
00437 {
00438     i2Cdev.readByte(devAddr, MPU6050_RA_FF_THR, buffer);
00439     return buffer[0];
00440 }
00441 /** Get free-fall event acceleration threshold.
00442  * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
00443  * @see getFreefallDetectionThreshold()
00444  * @see MPU6050_RA_FF_THR
00445  */
00446 void MPU6050::setFreefallDetectionThreshold(uint8_t threshold)
00447 {
00448     i2Cdev.writeByte(devAddr, MPU6050_RA_FF_THR, threshold);
00449 }
00450 
00451 // FF_DUR register
00452 
00453 /** Get free-fall event duration threshold.
00454  * This register configures the duration counter threshold for Free Fall event
00455  * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
00456  * of 1 LSB = 1 ms.
00457  *
00458  * The Free Fall duration counter increments while the absolute value of the
00459  * accelerometer measurements are each less than the detection threshold
00460  * (Register 29). The Free Fall interrupt is triggered when the Free Fall
00461  * duration counter reaches the time specified in this register.
00462  *
00463  * For more details on the Free Fall detection interrupt, see Section 8.2 of
00464  * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
00465  * and 58 of this document.
00466  *
00467  * @return Current free-fall duration threshold value (LSB = 1ms)
00468  * @see MPU6050_RA_FF_DUR
00469  */
00470 uint8_t MPU6050::getFreefallDetectionDuration()
00471 {
00472     i2Cdev.readByte(devAddr, MPU6050_RA_FF_DUR, buffer);
00473     return buffer[0];
00474 }
00475 /** Get free-fall event duration threshold.
00476  * @param duration New free-fall duration threshold value (LSB = 1ms)
00477  * @see getFreefallDetectionDuration()
00478  * @see MPU6050_RA_FF_DUR
00479  */
00480 void MPU6050::setFreefallDetectionDuration(uint8_t duration)
00481 {
00482     i2Cdev.writeByte(devAddr, MPU6050_RA_FF_DUR, duration);
00483 }
00484 
00485 // MOT_THR register
00486 
00487 /** Get motion detection event acceleration threshold.
00488  * This register configures the detection threshold for Motion interrupt
00489  * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
00490  * absolute value of any of the accelerometer measurements exceeds this Motion
00491  * detection threshold. This condition increments the Motion detection duration
00492  * counter (Register 32). The Motion detection interrupt is triggered when the
00493  * Motion Detection counter reaches the time count specified in MOT_DUR
00494  * (Register 32).
00495  *
00496  * The Motion interrupt will indicate the axis and polarity of detected motion
00497  * in MOT_DETECT_STATUS (Register 97).
00498  *
00499  * For more details on the Motion detection interrupt, see Section 8.3 of the
00500  * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
00501  * 58 of this document.
00502  *
00503  * @return Current motion detection acceleration threshold value (LSB = 2mg)
00504  * @see MPU6050_RA_MOT_THR
00505  */
00506 uint8_t MPU6050::getMotionDetectionThreshold()
00507 {
00508     i2Cdev.readByte(devAddr, MPU6050_RA_MOT_THR, buffer);
00509     return buffer[0];
00510 }
00511 /** Set free-fall event acceleration threshold.
00512  * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
00513  * @see getMotionDetectionThreshold()
00514  * @see MPU6050_RA_MOT_THR
00515  */
00516 void MPU6050::setMotionDetectionThreshold(uint8_t threshold)
00517 {
00518     i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_THR, threshold);
00519 }
00520 
00521 // MOT_DUR register
00522 
00523 /** Get motion detection event duration threshold.
00524  * This register configures the duration counter threshold for Motion interrupt
00525  * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
00526  * of 1LSB = 1ms. The Motion detection duration counter increments when the
00527  * absolute value of any of the accelerometer measurements exceeds the Motion
00528  * detection threshold (Register 31). The Motion detection interrupt is
00529  * triggered when the Motion detection counter reaches the time count specified
00530  * in this register.
00531  *
00532  * For more details on the Motion detection interrupt, see Section 8.3 of the
00533  * MPU-6000/MPU-6050 Product Specification document.
00534  *
00535  * @return Current motion detection duration threshold value (LSB = 1ms)
00536  * @see MPU6050_RA_MOT_DUR
00537  */
00538 uint8_t MPU6050::getMotionDetectionDuration()
00539 {
00540     i2Cdev.readByte(devAddr, MPU6050_RA_MOT_DUR, buffer);
00541     return buffer[0];
00542 }
00543 /** Set motion detection event duration threshold.
00544  * @param duration New motion detection duration threshold value (LSB = 1ms)
00545  * @see getMotionDetectionDuration()
00546  * @see MPU6050_RA_MOT_DUR
00547  */
00548 void MPU6050::setMotionDetectionDuration(uint8_t duration)
00549 {
00550     i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_DUR, duration);
00551 }
00552 
00553 // ZRMOT_THR register
00554 
00555 /** Get zero motion detection event acceleration threshold.
00556  * This register configures the detection threshold for Zero Motion interrupt
00557  * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
00558  * the absolute value of the accelerometer measurements for the 3 axes are each
00559  * less than the detection threshold. This condition increments the Zero Motion
00560  * duration counter (Register 34). The Zero Motion interrupt is triggered when
00561  * the Zero Motion duration counter reaches the time count specified in
00562  * ZRMOT_DUR (Register 34).
00563  *
00564  * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
00565  * interrupt both when Zero Motion is first detected and when Zero Motion is no
00566  * longer detected.
00567  *
00568  * When a zero motion event is detected, a Zero Motion Status will be indicated
00569  * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
00570  * condition is detected, the status bit is set to 1. When a zero-motion-to-
00571  * motion condition is detected, the status bit is set to 0.
00572  *
00573  * For more details on the Zero Motion detection interrupt, see Section 8.4 of
00574  * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
00575  * and 58 of this document.
00576  *
00577  * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
00578  * @see MPU6050_RA_ZRMOT_THR
00579  */
00580 uint8_t MPU6050::getZeroMotionDetectionThreshold()
00581 {
00582     i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer);
00583     return buffer[0];
00584 }
00585 /** Set zero motion detection event acceleration threshold.
00586  * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
00587  * @see getZeroMotionDetectionThreshold()
00588  * @see MPU6050_RA_ZRMOT_THR
00589  */
00590 void MPU6050::setZeroMotionDetectionThreshold(uint8_t threshold)
00591 {
00592     i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold);
00593 }
00594 
00595 // ZRMOT_DUR register
00596 
00597 /** Get zero motion detection event duration threshold.
00598  * This register configures the duration counter threshold for Zero Motion
00599  * interrupt generation. The duration counter ticks at 16 Hz, therefore
00600  * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
00601  * increments while the absolute value of the accelerometer measurements are
00602  * each less than the detection threshold (Register 33). The Zero Motion
00603  * interrupt is triggered when the Zero Motion duration counter reaches the time
00604  * count specified in this register.
00605  *
00606  * For more details on the Zero Motion detection interrupt, see Section 8.4 of
00607  * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
00608  * and 58 of this document.
00609  *
00610  * @return Current zero motion detection duration threshold value (LSB = 64ms)
00611  * @see MPU6050_RA_ZRMOT_DUR
00612  */
00613 uint8_t MPU6050::getZeroMotionDetectionDuration()
00614 {
00615     i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer);
00616     return buffer[0];
00617 }
00618 /** Set zero motion detection event duration threshold.
00619  * @param duration New zero motion detection duration threshold value (LSB = 1ms)
00620  * @see getZeroMotionDetectionDuration()
00621  * @see MPU6050_RA_ZRMOT_DUR
00622  */
00623 void MPU6050::setZeroMotionDetectionDuration(uint8_t duration)
00624 {
00625     i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration);
00626 }
00627 
00628 // FIFO_EN register
00629 
00630 /** Get temperature FIFO enabled value.
00631  * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
00632  * 66) to be written into the FIFO buffer.
00633  * @return Current temperature FIFO enabled value
00634  * @see MPU6050_RA_FIFO_EN
00635  */
00636 bool MPU6050::getTempFIFOEnabled()
00637 {
00638     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer);
00639     return buffer[0];
00640 }
00641 /** Set temperature FIFO enabled value.
00642  * @param enabled New temperature FIFO enabled value
00643  * @see getTempFIFOEnabled()
00644  * @see MPU6050_RA_FIFO_EN
00645  */
00646 void MPU6050::setTempFIFOEnabled(bool enabled)
00647 {
00648     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled);
00649 }
00650 /** Get gyroscope X-axis FIFO enabled value.
00651  * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
00652  * 68) to be written into the FIFO buffer.
00653  * @return Current gyroscope X-axis FIFO enabled value
00654  * @see MPU6050_RA_FIFO_EN
00655  */
00656 bool MPU6050::getXGyroFIFOEnabled()
00657 {
00658     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer);
00659     return buffer[0];
00660 }
00661 /** Set gyroscope X-axis FIFO enabled value.
00662  * @param enabled New gyroscope X-axis FIFO enabled value
00663  * @see getXGyroFIFOEnabled()
00664  * @see MPU6050_RA_FIFO_EN
00665  */
00666 void MPU6050::setXGyroFIFOEnabled(bool enabled)
00667 {
00668     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled);
00669 }
00670 /** Get gyroscope Y-axis FIFO enabled value.
00671  * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
00672  * 70) to be written into the FIFO buffer.
00673  * @return Current gyroscope Y-axis FIFO enabled value
00674  * @see MPU6050_RA_FIFO_EN
00675  */
00676 bool MPU6050::getYGyroFIFOEnabled()
00677 {
00678     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer);
00679     return buffer[0];
00680 }
00681 /** Set gyroscope Y-axis FIFO enabled value.
00682  * @param enabled New gyroscope Y-axis FIFO enabled value
00683  * @see getYGyroFIFOEnabled()
00684  * @see MPU6050_RA_FIFO_EN
00685  */
00686 void MPU6050::setYGyroFIFOEnabled(bool enabled)
00687 {
00688     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled);
00689 }
00690 /** Get gyroscope Z-axis FIFO enabled value.
00691  * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
00692  * 72) to be written into the FIFO buffer.
00693  * @return Current gyroscope Z-axis FIFO enabled value
00694  * @see MPU6050_RA_FIFO_EN
00695  */
00696 bool MPU6050::getZGyroFIFOEnabled()
00697 {
00698     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer);
00699     return buffer[0];
00700 }
00701 /** Set gyroscope Z-axis FIFO enabled value.
00702  * @param enabled New gyroscope Z-axis FIFO enabled value
00703  * @see getZGyroFIFOEnabled()
00704  * @see MPU6050_RA_FIFO_EN
00705  */
00706 void MPU6050::setZGyroFIFOEnabled(bool enabled)
00707 {
00708     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled);
00709 }
00710 /** Get accelerometer FIFO enabled value.
00711  * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
00712  * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
00713  * written into the FIFO buffer.
00714  * @return Current accelerometer FIFO enabled value
00715  * @see MPU6050_RA_FIFO_EN
00716  */
00717 bool MPU6050::getAccelFIFOEnabled()
00718 {
00719     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer);
00720     return buffer[0];
00721 }
00722 /** Set accelerometer FIFO enabled value.
00723  * @param enabled New accelerometer FIFO enabled value
00724  * @see getAccelFIFOEnabled()
00725  * @see MPU6050_RA_FIFO_EN
00726  */
00727 void MPU6050::setAccelFIFOEnabled(bool enabled)
00728 {
00729     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled);
00730 }
00731 /** Get Slave 2 FIFO enabled value.
00732  * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
00733  * associated with Slave 2 to be written into the FIFO buffer.
00734  * @return Current Slave 2 FIFO enabled value
00735  * @see MPU6050_RA_FIFO_EN
00736  */
00737 bool MPU6050::getSlave2FIFOEnabled()
00738 {
00739     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer);
00740     return buffer[0];
00741 }
00742 /** Set Slave 2 FIFO enabled value.
00743  * @param enabled New Slave 2 FIFO enabled value
00744  * @see getSlave2FIFOEnabled()
00745  * @see MPU6050_RA_FIFO_EN
00746  */
00747 void MPU6050::setSlave2FIFOEnabled(bool enabled)
00748 {
00749     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled);
00750 }
00751 /** Get Slave 1 FIFO enabled value.
00752  * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
00753  * associated with Slave 1 to be written into the FIFO buffer.
00754  * @return Current Slave 1 FIFO enabled value
00755  * @see MPU6050_RA_FIFO_EN
00756  */
00757 bool MPU6050::getSlave1FIFOEnabled()
00758 {
00759     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer);
00760     return buffer[0];
00761 }
00762 /** Set Slave 1 FIFO enabled value.
00763  * @param enabled New Slave 1 FIFO enabled value
00764  * @see getSlave1FIFOEnabled()
00765  * @see MPU6050_RA_FIFO_EN
00766  */
00767 void MPU6050::setSlave1FIFOEnabled(bool enabled)
00768 {
00769     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled);
00770 }
00771 /** Get Slave 0 FIFO enabled value.
00772  * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
00773  * associated with Slave 0 to be written into the FIFO buffer.
00774  * @return Current Slave 0 FIFO enabled value
00775  * @see MPU6050_RA_FIFO_EN
00776  */
00777 bool MPU6050::getSlave0FIFOEnabled()
00778 {
00779     i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer);
00780     return buffer[0];
00781 }
00782 /** Set Slave 0 FIFO enabled value.
00783  * @param enabled New Slave 0 FIFO enabled value
00784  * @see getSlave0FIFOEnabled()
00785  * @see MPU6050_RA_FIFO_EN
00786  */
00787 void MPU6050::setSlave0FIFOEnabled(bool enabled)
00788 {
00789     i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled);
00790 }
00791 
00792 // I2C_MST_CTRL register
00793 
00794 /** Get multi-master enabled value.
00795  * Multi-master capability allows multiple I2C masters to operate on the same
00796  * bus. In circuits where multi-master capability is required, set MULT_MST_EN
00797  * to 1. This will increase current drawn by approximately 30uA.
00798  *
00799  * In circuits where multi-master capability is required, the state of the I2C
00800  * bus must always be monitored by each separate I2C Master. Before an I2C
00801  * Master can assume arbitration of the bus, it must first confirm that no other
00802  * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
00803  * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
00804  * detect when the bus is available.
00805  *
00806  * @return Current multi-master enabled value
00807  * @see MPU6050_RA_I2C_MST_CTRL
00808  */
00809 bool MPU6050::getMultiMasterEnabled()
00810 {
00811     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer);
00812     return buffer[0];
00813 }
00814 /** Set multi-master enabled value.
00815  * @param enabled New multi-master enabled value
00816  * @see getMultiMasterEnabled()
00817  * @see MPU6050_RA_I2C_MST_CTRL
00818  */
00819 void MPU6050::setMultiMasterEnabled(bool enabled)
00820 {
00821     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled);
00822 }
00823 /** Get wait-for-external-sensor-data enabled value.
00824  * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
00825  * delayed until External Sensor data from the Slave Devices are loaded into the
00826  * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
00827  * data (i.e. from gyro and accel) and external sensor data have been loaded to
00828  * their respective data registers (i.e. the data is synced) when the Data Ready
00829  * interrupt is triggered.
00830  *
00831  * @return Current wait-for-external-sensor-data enabled value
00832  * @see MPU6050_RA_I2C_MST_CTRL
00833  */
00834 bool MPU6050::getWaitForExternalSensorEnabled()
00835 {
00836     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer);
00837     return buffer[0];
00838 }
00839 /** Set wait-for-external-sensor-data enabled value.
00840  * @param enabled New wait-for-external-sensor-data enabled value
00841  * @see getWaitForExternalSensorEnabled()
00842  * @see MPU6050_RA_I2C_MST_CTRL
00843  */
00844 void MPU6050::setWaitForExternalSensorEnabled(bool enabled)
00845 {
00846     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled);
00847 }
00848 /** Get Slave 3 FIFO enabled value.
00849  * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
00850  * associated with Slave 3 to be written into the FIFO buffer.
00851  * @return Current Slave 3 FIFO enabled value
00852  * @see MPU6050_RA_MST_CTRL
00853  */
00854 bool MPU6050::getSlave3FIFOEnabled()
00855 {
00856     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer);
00857     return buffer[0];
00858 }
00859 /** Set Slave 3 FIFO enabled value.
00860  * @param enabled New Slave 3 FIFO enabled value
00861  * @see getSlave3FIFOEnabled()
00862  * @see MPU6050_RA_MST_CTRL
00863  */
00864 void MPU6050::setSlave3FIFOEnabled(bool enabled)
00865 {
00866     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled);
00867 }
00868 /** Get slave read/write transition enabled value.
00869  * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
00870  * read to the next slave read. If the bit equals 0, there will be a restart
00871  * between reads. If the bit equals 1, there will be a stop followed by a start
00872  * of the following read. When a write transaction follows a read transaction,
00873  * the stop followed by a start of the successive write will be always used.
00874  *
00875  * @return Current slave read/write transition enabled value
00876  * @see MPU6050_RA_I2C_MST_CTRL
00877  */
00878 bool MPU6050::getSlaveReadWriteTransitionEnabled()
00879 {
00880     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer);
00881     return buffer[0];
00882 }
00883 /** Set slave read/write transition enabled value.
00884  * @param enabled New slave read/write transition enabled value
00885  * @see getSlaveReadWriteTransitionEnabled()
00886  * @see MPU6050_RA_I2C_MST_CTRL
00887  */
00888 void MPU6050::setSlaveReadWriteTransitionEnabled(bool enabled)
00889 {
00890     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled);
00891 }
00892 /** Get I2C master clock speed.
00893  * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
00894  * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
00895  * the following table:
00896  *
00897  * <pre>
00898  * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
00899  * ------------+------------------------+-------------------
00900  * 0           | 348kHz                 | 23
00901  * 1           | 333kHz                 | 24
00902  * 2           | 320kHz                 | 25
00903  * 3           | 308kHz                 | 26
00904  * 4           | 296kHz                 | 27
00905  * 5           | 286kHz                 | 28
00906  * 6           | 276kHz                 | 29
00907  * 7           | 267kHz                 | 30
00908  * 8           | 258kHz                 | 31
00909  * 9           | 500kHz                 | 16
00910  * 10          | 471kHz                 | 17
00911  * 11          | 444kHz                 | 18
00912  * 12          | 421kHz                 | 19
00913  * 13          | 400kHz                 | 20
00914  * 14          | 381kHz                 | 21
00915  * 15          | 364kHz                 | 22
00916  * </pre>
00917  *
00918  * @return Current I2C master clock speed
00919  * @see MPU6050_RA_I2C_MST_CTRL
00920  */
00921 uint8_t MPU6050::getMasterClockSpeed()
00922 {
00923     i2Cdev.readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer);
00924     return buffer[0];
00925 }
00926 /** Set I2C master clock speed.
00927  * @reparam speed Current I2C master clock speed
00928  * @see MPU6050_RA_I2C_MST_CTRL
00929  */
00930 void MPU6050::setMasterClockSpeed(uint8_t speed)
00931 {
00932     i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed);
00933 }
00934 
00935 // I2C_SLV* registers (Slave 0-3)
00936 
00937 /** Get the I2C address of the specified slave (0-3).
00938  * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
00939  * operation, and if it is cleared, then it's a write operation. The remaining
00940  * bits (6-0) are the 7-bit device address of the slave device.
00941  *
00942  * In read mode, the result of the read is placed in the lowest available
00943  * EXT_SENS_DATA register. For further information regarding the allocation of
00944  * read results, please refer to the EXT_SENS_DATA register description
00945  * (Registers 73 - 96).
00946  *
00947  * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
00948  * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
00949  *
00950  * I2C data transactions are performed at the Sample Rate, as defined in
00951  * Register 25. The user is responsible for ensuring that I2C data transactions
00952  * to and from each enabled Slave can be completed within a single period of the
00953  * Sample Rate.
00954  *
00955  * The I2C slave access rate can be reduced relative to the Sample Rate. This
00956  * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
00957  * slave's access rate is reduced relative to the Sample Rate is determined by
00958  * I2C_MST_DELAY_CTRL (Register 103).
00959  *
00960  * The processing order for the slaves is fixed. The sequence followed for
00961  * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
00962  * particular Slave is disabled it will be skipped.
00963  *
00964  * Each slave can either be accessed at the sample rate or at a reduced sample
00965  * rate. In a case where some slaves are accessed at the Sample Rate and some
00966  * slaves are accessed at the reduced rate, the sequence of accessing the slaves
00967  * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
00968  * be skipped if their access rate dictates that they should not be accessed
00969  * during that particular cycle. For further information regarding the reduced
00970  * access rate, please refer to Register 52. Whether a slave is accessed at the
00971  * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
00972  * Register 103.
00973  *
00974  * @param num Slave number (0-3)
00975  * @return Current address for specified slave
00976  * @see MPU6050_RA_I2C_SLV0_ADDR
00977  */
00978 uint8_t MPU6050::getSlaveAddress(uint8_t num)
00979 {
00980     if (num > 3) return 0;
00981     i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer);
00982     return buffer[0];
00983 }
00984 /** Set the I2C address of the specified slave (0-3).
00985  * @param num Slave number (0-3)
00986  * @param address New address for specified slave
00987  * @see getSlaveAddress()
00988  * @see MPU6050_RA_I2C_SLV0_ADDR
00989  */
00990 void MPU6050::setSlaveAddress(uint8_t num, uint8_t address)
00991 {
00992     if (num > 3) return;
00993     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address);
00994 }
00995 /** Get the active internal register for the specified slave (0-3).
00996  * Read/write operations for this slave will be done to whatever internal
00997  * register address is stored in this MPU register.
00998  *
00999  * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
01000  * characteristics, and so it has its own functions.
01001  *
01002  * @param num Slave number (0-3)
01003  * @return Current active register for specified slave
01004  * @see MPU6050_RA_I2C_SLV0_REG
01005  */
01006 uint8_t MPU6050::getSlaveRegister(uint8_t num)
01007 {
01008     if (num > 3) return 0;
01009     i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer);
01010     return buffer[0];
01011 }
01012 /** Set the active internal register for the specified slave (0-3).
01013  * @param num Slave number (0-3)
01014  * @param reg New active register for specified slave
01015  * @see getSlaveRegister()
01016  * @see MPU6050_RA_I2C_SLV0_REG
01017  */
01018 void MPU6050::setSlaveRegister(uint8_t num, uint8_t reg)
01019 {
01020     if (num > 3) return;
01021     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg);
01022 }
01023 /** Get the enabled value for the specified slave (0-3).
01024  * When set to 1, this bit enables Slave 0 for data transfer operations. When
01025  * cleared to 0, this bit disables Slave 0 from data transfer operations.
01026  * @param num Slave number (0-3)
01027  * @return Current enabled value for specified slave
01028  * @see MPU6050_RA_I2C_SLV0_CTRL
01029  */
01030 bool MPU6050::getSlaveEnabled(uint8_t num)
01031 {
01032     if (num > 3) return 0;
01033     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer);
01034     return buffer[0];
01035 }
01036 /** Set the enabled value for the specified slave (0-3).
01037  * @param num Slave number (0-3)
01038  * @param enabled New enabled value for specified slave 
01039  * @see getSlaveEnabled()
01040  * @see MPU6050_RA_I2C_SLV0_CTRL
01041  */
01042 void MPU6050::setSlaveEnabled(uint8_t num, bool enabled)
01043 {
01044     if (num > 3) return;
01045     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled);
01046 }
01047 /** Get word pair byte-swapping enabled for the specified slave (0-3).
01048  * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
01049  * the high and low bytes of a word pair are swapped. Please refer to
01050  * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
01051  * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
01052  * registers in the order they were transferred.
01053  *
01054  * @param num Slave number (0-3)
01055  * @return Current word pair byte-swapping enabled value for specified slave
01056  * @see MPU6050_RA_I2C_SLV0_CTRL
01057  */
01058 bool MPU6050::getSlaveWordByteSwap(uint8_t num)
01059 {
01060     if (num > 3) return 0;
01061     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer);
01062     return buffer[0];
01063 }
01064 /** Set word pair byte-swapping enabled for the specified slave (0-3).
01065  * @param num Slave number (0-3)
01066  * @param enabled New word pair byte-swapping enabled value for specified slave
01067  * @see getSlaveWordByteSwap()
01068  * @see MPU6050_RA_I2C_SLV0_CTRL
01069  */
01070 void MPU6050::setSlaveWordByteSwap(uint8_t num, bool enabled)
01071 {
01072     if (num > 3) return;
01073     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled);
01074 }
01075 /** Get write mode for the specified slave (0-3).
01076  * When set to 1, the transaction will read or write data only. When cleared to
01077  * 0, the transaction will write a register address prior to reading or writing
01078  * data. This should equal 0 when specifying the register address within the
01079  * Slave device to/from which the ensuing data transaction will take place.
01080  *
01081  * @param num Slave number (0-3)
01082  * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
01083  * @see MPU6050_RA_I2C_SLV0_CTRL
01084  */
01085 bool MPU6050::getSlaveWriteMode(uint8_t num)
01086 {
01087     if (num > 3) return 0;
01088     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer);
01089     return buffer[0];
01090 }
01091 /** Set write mode for the specified slave (0-3).
01092  * @param num Slave number (0-3)
01093  * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
01094  * @see getSlaveWriteMode()
01095  * @see MPU6050_RA_I2C_SLV0_CTRL
01096  */
01097 void MPU6050::setSlaveWriteMode(uint8_t num, bool mode)
01098 {
01099     if (num > 3) return;
01100     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode);
01101 }
01102 /** Get word pair grouping order offset for the specified slave (0-3).
01103  * This sets specifies the grouping order of word pairs received from registers.
01104  * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
01105  * then odd register addresses) are paired to form a word. When set to 1, bytes
01106  * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
01107  * register addresses) are paired to form a word.
01108  *
01109  * @param num Slave number (0-3)
01110  * @return Current word pair grouping order offset for specified slave
01111  * @see MPU6050_RA_I2C_SLV0_CTRL
01112  */
01113 bool MPU6050::getSlaveWordGroupOffset(uint8_t num)
01114 {
01115     if (num > 3) return 0;
01116     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer);
01117     return buffer[0];
01118 }
01119 /** Set word pair grouping order offset for the specified slave (0-3).
01120  * @param num Slave number (0-3)
01121  * @param enabled New word pair grouping order offset for specified slave
01122  * @see getSlaveWordGroupOffset()
01123  * @see MPU6050_RA_I2C_SLV0_CTRL
01124  */
01125 void MPU6050::setSlaveWordGroupOffset(uint8_t num, bool enabled)
01126 {
01127     if (num > 3) return;
01128     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled);
01129 }
01130 /** Get number of bytes to read for the specified slave (0-3).
01131  * Specifies the number of bytes transferred to and from Slave 0. Clearing this
01132  * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
01133  * @param num Slave number (0-3)
01134  * @return Number of bytes to read for specified slave
01135  * @see MPU6050_RA_I2C_SLV0_CTRL
01136  */
01137 uint8_t MPU6050::getSlaveDataLength(uint8_t num)
01138 {
01139     if (num > 3) return 0;
01140     i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer);
01141     return buffer[0];
01142 }
01143 /** Set number of bytes to read for the specified slave (0-3).
01144  * @param num Slave number (0-3)
01145  * @param length Number of bytes to read for specified slave
01146  * @see getSlaveDataLength()
01147  * @see MPU6050_RA_I2C_SLV0_CTRL
01148  */
01149 void MPU6050::setSlaveDataLength(uint8_t num, uint8_t length)
01150 {
01151     if (num > 3) return;
01152     i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length);
01153 }
01154 
01155 // I2C_SLV* registers (Slave 4)
01156 
01157 /** Get the I2C address of Slave 4.
01158  * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
01159  * operation, and if it is cleared, then it's a write operation. The remaining
01160  * bits (6-0) are the 7-bit device address of the slave device.
01161  *
01162  * @return Current address for Slave 4
01163  * @see getSlaveAddress()
01164  * @see MPU6050_RA_I2C_SLV4_ADDR
01165  */
01166 uint8_t MPU6050::getSlave4Address()
01167 {
01168     i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer);
01169     return buffer[0];
01170 }
01171 /** Set the I2C address of Slave 4.
01172  * @param address New address for Slave 4
01173  * @see getSlave4Address()
01174  * @see MPU6050_RA_I2C_SLV4_ADDR
01175  */
01176 void MPU6050::setSlave4Address(uint8_t address)
01177 {
01178     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address);
01179 }
01180 /** Get the active internal register for the Slave 4.
01181  * Read/write operations for this slave will be done to whatever internal
01182  * register address is stored in this MPU register.
01183  *
01184  * @return Current active register for Slave 4
01185  * @see MPU6050_RA_I2C_SLV4_REG
01186  */
01187 uint8_t MPU6050::getSlave4Register()
01188 {
01189     i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer);
01190     return buffer[0];
01191 }
01192 /** Set the active internal register for Slave 4.
01193  * @param reg New active register for Slave 4
01194  * @see getSlave4Register()
01195  * @see MPU6050_RA_I2C_SLV4_REG
01196  */
01197 void MPU6050::setSlave4Register(uint8_t reg)
01198 {
01199     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg);
01200 }
01201 /** Set new byte to write to Slave 4.
01202  * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
01203  * is set 1 (set to read), this register has no effect.
01204  * @param data New byte to write to Slave 4
01205  * @see MPU6050_RA_I2C_SLV4_DO
01206  */
01207 void MPU6050::setSlave4OutputByte(uint8_t data)
01208 {
01209     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data);
01210 }
01211 /** Get the enabled value for the Slave 4.
01212  * When set to 1, this bit enables Slave 4 for data transfer operations. When
01213  * cleared to 0, this bit disables Slave 4 from data transfer operations.
01214  * @return Current enabled value for Slave 4
01215  * @see MPU6050_RA_I2C_SLV4_CTRL
01216  */
01217 bool MPU6050::getSlave4Enabled()
01218 {
01219     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer);
01220     return buffer[0];
01221 }
01222 /** Set the enabled value for Slave 4.
01223  * @param enabled New enabled value for Slave 4
01224  * @see getSlave4Enabled()
01225  * @see MPU6050_RA_I2C_SLV4_CTRL
01226  */
01227 void MPU6050::setSlave4Enabled(bool enabled)
01228 {
01229     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled);
01230 }
01231 /** Get the enabled value for Slave 4 transaction interrupts.
01232  * When set to 1, this bit enables the generation of an interrupt signal upon
01233  * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
01234  * generation of an interrupt signal upon completion of a Slave 4 transaction.
01235  * The interrupt status can be observed in Register 54.
01236  *
01237  * @return Current enabled value for Slave 4 transaction interrupts.
01238  * @see MPU6050_RA_I2C_SLV4_CTRL
01239  */
01240 bool MPU6050::getSlave4InterruptEnabled()
01241 {
01242     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer);
01243     return buffer[0];
01244 }
01245 /** Set the enabled value for Slave 4 transaction interrupts.
01246  * @param enabled New enabled value for Slave 4 transaction interrupts.
01247  * @see getSlave4InterruptEnabled()
01248  * @see MPU6050_RA_I2C_SLV4_CTRL
01249  */
01250 void MPU6050::setSlave4InterruptEnabled(bool enabled)
01251 {
01252     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled);
01253 }
01254 /** Get write mode for Slave 4.
01255  * When set to 1, the transaction will read or write data only. When cleared to
01256  * 0, the transaction will write a register address prior to reading or writing
01257  * data. This should equal 0 when specifying the register address within the
01258  * Slave device to/from which the ensuing data transaction will take place.
01259  *
01260  * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
01261  * @see MPU6050_RA_I2C_SLV4_CTRL
01262  */
01263 bool MPU6050::getSlave4WriteMode()
01264 {
01265     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer);
01266     return buffer[0];
01267 }
01268 /** Set write mode for the Slave 4.
01269  * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
01270  * @see getSlave4WriteMode()
01271  * @see MPU6050_RA_I2C_SLV4_CTRL
01272  */
01273 void MPU6050::setSlave4WriteMode(bool mode)
01274 {
01275     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode);
01276 }
01277 /** Get Slave 4 master delay value.
01278  * This configures the reduced access rate of I2C slaves relative to the Sample
01279  * Rate. When a slave's access rate is decreased relative to the Sample Rate,
01280  * the slave is accessed every:
01281  *
01282  *     1 / (1 + I2C_MST_DLY) samples
01283  *
01284  * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
01285  * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
01286  * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
01287  * further information regarding the Sample Rate, please refer to register 25.
01288  *
01289  * @return Current Slave 4 master delay value
01290  * @see MPU6050_RA_I2C_SLV4_CTRL
01291  */
01292 uint8_t MPU6050::getSlave4MasterDelay()
01293 {
01294     i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer);
01295     return buffer[0];
01296 }
01297 /** Set Slave 4 master delay value.
01298  * @param delay New Slave 4 master delay value
01299  * @see getSlave4MasterDelay()
01300  * @see MPU6050_RA_I2C_SLV4_CTRL
01301  */
01302 void MPU6050::setSlave4MasterDelay(uint8_t delay)
01303 {
01304     i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay);
01305 }
01306 /** Get last available byte read from Slave 4.
01307  * This register stores the data read from Slave 4. This field is populated
01308  * after a read transaction.
01309  * @return Last available byte read from to Slave 4
01310  * @see MPU6050_RA_I2C_SLV4_DI
01311  */
01312 uint8_t MPU6050::getSlate4InputByte()
01313 {
01314     i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer);
01315     return buffer[0];
01316 }
01317 
01318 // I2C_MST_STATUS register
01319 
01320 /** Get FSYNC interrupt status.
01321  * This bit reflects the status of the FSYNC interrupt from an external device
01322  * into the MPU-60X0. This is used as a way to pass an external interrupt
01323  * through the MPU-60X0 to the host application processor. When set to 1, this
01324  * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
01325  * (Register 55).
01326  * @return FSYNC interrupt status
01327  * @see MPU6050_RA_I2C_MST_STATUS
01328  */
01329 bool MPU6050::getPassthroughStatus()
01330 {
01331     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer);
01332     return buffer[0];
01333 }
01334 /** Get Slave 4 transaction done status.
01335  * Automatically sets to 1 when a Slave 4 transaction has completed. This
01336  * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
01337  * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
01338  * I2C_SLV4_CTRL register (Register 52).
01339  * @return Slave 4 transaction done status
01340  * @see MPU6050_RA_I2C_MST_STATUS
01341  */
01342 bool MPU6050::getSlave4IsDone()
01343 {
01344     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer);
01345     return buffer[0];
01346 }
01347 /** Get master arbitration lost status.
01348  * This bit automatically sets to 1 when the I2C Master has lost arbitration of
01349  * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
01350  * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
01351  * @return Master arbitration lost status
01352  * @see MPU6050_RA_I2C_MST_STATUS
01353  */
01354 bool MPU6050::getLostArbitration()
01355 {
01356     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer);
01357     return buffer[0];
01358 }
01359 /** Get Slave 4 NACK status.
01360  * This bit automatically sets to 1 when the I2C Master receives a NACK in a
01361  * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
01362  * bit in the INT_ENABLE register (Register 56) is asserted.
01363  * @return Slave 4 NACK interrupt status
01364  * @see MPU6050_RA_I2C_MST_STATUS
01365  */
01366 bool MPU6050::getSlave4Nack()
01367 {
01368     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer);
01369     return buffer[0];
01370 }
01371 /** Get Slave 3 NACK status.
01372  * This bit automatically sets to 1 when the I2C Master receives a NACK in a
01373  * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
01374  * bit in the INT_ENABLE register (Register 56) is asserted.
01375  * @return Slave 3 NACK interrupt status
01376  * @see MPU6050_RA_I2C_MST_STATUS
01377  */
01378 bool MPU6050::getSlave3Nack()
01379 {
01380     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer);
01381     return buffer[0];
01382 }
01383 /** Get Slave 2 NACK status.
01384  * This bit automatically sets to 1 when the I2C Master receives a NACK in a
01385  * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
01386  * bit in the INT_ENABLE register (Register 56) is asserted.
01387  * @return Slave 2 NACK interrupt status
01388  * @see MPU6050_RA_I2C_MST_STATUS
01389  */
01390 bool MPU6050::getSlave2Nack()
01391 {
01392     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer);
01393     return buffer[0];
01394 }
01395 /** Get Slave 1 NACK status.
01396  * This bit automatically sets to 1 when the I2C Master receives a NACK in a
01397  * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
01398  * bit in the INT_ENABLE register (Register 56) is asserted.
01399  * @return Slave 1 NACK interrupt status
01400  * @see MPU6050_RA_I2C_MST_STATUS
01401  */
01402 bool MPU6050::getSlave1Nack()
01403 {
01404     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer);
01405     return buffer[0];
01406 }
01407 /** Get Slave 0 NACK status.
01408  * This bit automatically sets to 1 when the I2C Master receives a NACK in a
01409  * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
01410  * bit in the INT_ENABLE register (Register 56) is asserted.
01411  * @return Slave 0 NACK interrupt status
01412  * @see MPU6050_RA_I2C_MST_STATUS
01413  */
01414 bool MPU6050::getSlave0Nack()
01415 {
01416     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer);
01417     return buffer[0];
01418 }
01419 
01420 // INT_PIN_CFG register
01421 
01422 /** Get interrupt logic level mode.
01423  * Will be set 0 for active-high, 1 for active-low.
01424  * @return Current interrupt mode (0=active-high, 1=active-low)
01425  * @see MPU6050_RA_INT_PIN_CFG
01426  * @see MPU6050_INTCFG_INT_LEVEL_BIT
01427  */
01428 bool MPU6050::getInterruptMode()
01429 {
01430     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer);
01431     return buffer[0];
01432 }
01433 /** Set interrupt logic level mode.
01434  * @param mode New interrupt mode (0=active-high, 1=active-low)
01435  * @see getInterruptMode()
01436  * @see MPU6050_RA_INT_PIN_CFG
01437  * @see MPU6050_INTCFG_INT_LEVEL_BIT
01438  */
01439 void MPU6050::setInterruptMode(bool mode)
01440 {
01441     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode);
01442 }
01443 /** Get interrupt drive mode.
01444  * Will be set 0 for push-pull, 1 for open-drain.
01445  * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
01446  * @see MPU6050_RA_INT_PIN_CFG
01447  * @see MPU6050_INTCFG_INT_OPEN_BIT
01448  */
01449 bool MPU6050::getInterruptDrive()
01450 {
01451     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer);
01452     return buffer[0];
01453 }
01454 /** Set interrupt drive mode.
01455  * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
01456  * @see getInterruptDrive()
01457  * @see MPU6050_RA_INT_PIN_CFG
01458  * @see MPU6050_INTCFG_INT_OPEN_BIT
01459  */
01460 void MPU6050::setInterruptDrive(bool drive)
01461 {
01462     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive);
01463 }
01464 /** Get interrupt latch mode.
01465  * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
01466  * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
01467  * @see MPU6050_RA_INT_PIN_CFG
01468  * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
01469  */
01470 bool MPU6050::getInterruptLatch()
01471 {
01472     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer);
01473     return buffer[0];
01474 }
01475 /** Set interrupt latch mode.
01476  * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
01477  * @see getInterruptLatch()
01478  * @see MPU6050_RA_INT_PIN_CFG
01479  * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
01480  */
01481 void MPU6050::setInterruptLatch(bool latch)
01482 {
01483     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch);
01484 }
01485 /** Get interrupt latch clear mode.
01486  * Will be set 0 for status-read-only, 1 for any-register-read.
01487  * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
01488  * @see MPU6050_RA_INT_PIN_CFG
01489  * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
01490  */
01491 bool MPU6050::getInterruptLatchClear()
01492 {
01493     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer);
01494     return buffer[0];
01495 }
01496 /** Set interrupt latch clear mode.
01497  * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
01498  * @see getInterruptLatchClear()
01499  * @see MPU6050_RA_INT_PIN_CFG
01500  * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
01501  */
01502 void MPU6050::setInterruptLatchClear(bool clear)
01503 {
01504     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear);
01505 }
01506 /** Get FSYNC interrupt logic level mode.
01507  * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
01508  * @see getFSyncInterruptMode()
01509  * @see MPU6050_RA_INT_PIN_CFG
01510  * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
01511  */
01512 bool MPU6050::getFSyncInterruptLevel()
01513 {
01514     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
01515     return buffer[0];
01516 }
01517 /** Set FSYNC interrupt logic level mode.
01518  * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
01519  * @see getFSyncInterruptMode()
01520  * @see MPU6050_RA_INT_PIN_CFG
01521  * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
01522  */
01523 void MPU6050::setFSyncInterruptLevel(bool level)
01524 {
01525     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level);
01526 }
01527 /** Get FSYNC pin interrupt enabled setting.
01528  * Will be set 0 for disabled, 1 for enabled.
01529  * @return Current interrupt enabled setting
01530  * @see MPU6050_RA_INT_PIN_CFG
01531  * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
01532  */
01533 bool MPU6050::getFSyncInterruptEnabled()
01534 {
01535     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer);
01536     return buffer[0];
01537 }
01538 /** Set FSYNC pin interrupt enabled setting.
01539  * @param enabled New FSYNC pin interrupt enabled setting
01540  * @see getFSyncInterruptEnabled()
01541  * @see MPU6050_RA_INT_PIN_CFG
01542  * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
01543  */
01544 void MPU6050::setFSyncInterruptEnabled(bool enabled)
01545 {
01546     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled);
01547 }
01548 /** Get I2C bypass enabled status.
01549  * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
01550  * 0, the host application processor will be able to directly access the
01551  * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
01552  * application processor will not be able to directly access the auxiliary I2C
01553  * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
01554  * bit[5]).
01555  * @return Current I2C bypass enabled status
01556  * @see MPU6050_RA_INT_PIN_CFG
01557  * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
01558  */
01559 bool MPU6050::getI2CBypassEnabled()
01560 {
01561     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer);
01562     return buffer[0];
01563 }
01564 /** Set I2C bypass enabled status.
01565  * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
01566  * 0, the host application processor will be able to directly access the
01567  * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
01568  * application processor will not be able to directly access the auxiliary I2C
01569  * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
01570  * bit[5]).
01571  * @param enabled New I2C bypass enabled status
01572  * @see MPU6050_RA_INT_PIN_CFG
01573  * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
01574  */
01575 void MPU6050::setI2CBypassEnabled(bool enabled)
01576 {
01577     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled);
01578 }
01579 /** Get reference clock output enabled status.
01580  * When this bit is equal to 1, a reference clock output is provided at the
01581  * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
01582  * further information regarding CLKOUT, please refer to the MPU-60X0 Product
01583  * Specification document.
01584  * @return Current reference clock output enabled status
01585  * @see MPU6050_RA_INT_PIN_CFG
01586  * @see MPU6050_INTCFG_CLKOUT_EN_BIT
01587  */
01588 bool MPU6050::getClockOutputEnabled()
01589 {
01590     i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer);
01591     return buffer[0];
01592 }
01593 /** Set reference clock output enabled status.
01594  * When this bit is equal to 1, a reference clock output is provided at the
01595  * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
01596  * further information regarding CLKOUT, please refer to the MPU-60X0 Product
01597  * Specification document.
01598  * @param enabled New reference clock output enabled status
01599  * @see MPU6050_RA_INT_PIN_CFG
01600  * @see MPU6050_INTCFG_CLKOUT_EN_BIT
01601  */
01602 void MPU6050::setClockOutputEnabled(bool enabled)
01603 {
01604     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled);
01605 }
01606 
01607 // INT_ENABLE register
01608 
01609 /** Get full interrupt enabled status.
01610  * Full register byte for all interrupts, for quick reading. Each bit will be
01611  * set 0 for disabled, 1 for enabled.
01612  * @return Current interrupt enabled status
01613  * @see MPU6050_RA_INT_ENABLE
01614  * @see MPU6050_INTERRUPT_FF_BIT
01615  **/
01616 uint8_t MPU6050::getIntEnabled()
01617 {
01618     i2Cdev.readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer);
01619     return buffer[0];
01620 }
01621 /** Set full interrupt enabled status.
01622  * Full register byte for all interrupts, for quick reading. Each bit should be
01623  * set 0 for disabled, 1 for enabled.
01624  * @param enabled New interrupt enabled status
01625  * @see getIntFreefallEnabled()
01626  * @see MPU6050_RA_INT_ENABLE
01627  * @see MPU6050_INTERRUPT_FF_BIT
01628  **/
01629 void MPU6050::setIntEnabled(uint8_t enabled)
01630 {
01631     i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled);
01632 }
01633 /** Get Free Fall interrupt enabled status.
01634  * Will be set 0 for disabled, 1 for enabled.
01635  * @return Current interrupt enabled status
01636  * @see MPU6050_RA_INT_ENABLE
01637  * @see MPU6050_INTERRUPT_FF_BIT
01638  **/
01639 bool MPU6050::getIntFreefallEnabled()
01640 {
01641     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer);
01642     return buffer[0];
01643 }
01644 /** Set Free Fall interrupt enabled status.
01645  * @param enabled New interrupt enabled status
01646  * @see getIntFreefallEnabled()
01647  * @see MPU6050_RA_INT_ENABLE
01648  * @see MPU6050_INTERRUPT_FF_BIT
01649  **/
01650 void MPU6050::setIntFreefallEnabled(bool enabled)
01651 {
01652     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled);
01653 }
01654 /** Get Motion Detection interrupt enabled status.
01655  * Will be set 0 for disabled, 1 for enabled.
01656  * @return Current interrupt enabled status
01657  * @see MPU6050_RA_INT_ENABLE
01658  * @see MPU6050_INTERRUPT_MOT_BIT
01659  **/
01660 bool MPU6050::getIntMotionEnabled()
01661 {
01662     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer);
01663     return buffer[0];
01664 }
01665 /** Set Motion Detection interrupt enabled status.
01666  * @param enabled New interrupt enabled status
01667  * @see getIntMotionEnabled()
01668  * @see MPU6050_RA_INT_ENABLE
01669  * @see MPU6050_INTERRUPT_MOT_BIT
01670  **/
01671 void MPU6050::setIntMotionEnabled(bool enabled)
01672 {
01673     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled);
01674 }
01675 /** Get Zero Motion Detection interrupt enabled status.
01676  * Will be set 0 for disabled, 1 for enabled.
01677  * @return Current interrupt enabled status
01678  * @see MPU6050_RA_INT_ENABLE
01679  * @see MPU6050_INTERRUPT_ZMOT_BIT
01680  **/
01681 bool MPU6050::getIntZeroMotionEnabled()
01682 {
01683     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
01684     return buffer[0];
01685 }
01686 /** Set Zero Motion Detection interrupt enabled status.
01687  * @param enabled New interrupt enabled status
01688  * @see getIntZeroMotionEnabled()
01689  * @see MPU6050_RA_INT_ENABLE
01690  * @see MPU6050_INTERRUPT_ZMOT_BIT
01691  **/
01692 void MPU6050::setIntZeroMotionEnabled(bool enabled)
01693 {
01694     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled);
01695 }
01696 /** Get FIFO Buffer Overflow interrupt enabled status.
01697  * Will be set 0 for disabled, 1 for enabled.
01698  * @return Current interrupt enabled status
01699  * @see MPU6050_RA_INT_ENABLE
01700  * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
01701  **/
01702 bool MPU6050::getIntFIFOBufferOverflowEnabled()
01703 {
01704     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
01705     return buffer[0];
01706 }
01707 /** Set FIFO Buffer Overflow interrupt enabled status.
01708  * @param enabled New interrupt enabled status
01709  * @see getIntFIFOBufferOverflowEnabled()
01710  * @see MPU6050_RA_INT_ENABLE
01711  * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
01712  **/
01713 void MPU6050::setIntFIFOBufferOverflowEnabled(bool enabled)
01714 {
01715     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled);
01716 }
01717 /** Get I2C Master interrupt enabled status.
01718  * This enables any of the I2C Master interrupt sources to generate an
01719  * interrupt. Will be set 0 for disabled, 1 for enabled.
01720  * @return Current interrupt enabled status
01721  * @see MPU6050_RA_INT_ENABLE
01722  * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
01723  **/
01724 bool MPU6050::getIntI2CMasterEnabled()
01725 {
01726     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
01727     return buffer[0];
01728 }
01729 /** Set I2C Master interrupt enabled status.
01730  * @param enabled New interrupt enabled status
01731  * @see getIntI2CMasterEnabled()
01732  * @see MPU6050_RA_INT_ENABLE
01733  * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
01734  **/
01735 void MPU6050::setIntI2CMasterEnabled(bool enabled)
01736 {
01737     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled);
01738 }
01739 /** Get Data Ready interrupt enabled setting.
01740  * This event occurs each time a write operation to all of the sensor registers
01741  * has been completed. Will be set 0 for disabled, 1 for enabled.
01742  * @return Current interrupt enabled status
01743  * @see MPU6050_RA_INT_ENABLE
01744  * @see MPU6050_INTERRUPT_DATA_RDY_BIT
01745  */
01746 bool MPU6050::getIntDataReadyEnabled()
01747 {
01748     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
01749     return buffer[0];
01750 }
01751 /** Set Data Ready interrupt enabled status.
01752  * @param enabled New interrupt enabled status
01753  * @see getIntDataReadyEnabled()
01754  * @see MPU6050_RA_INT_CFG
01755  * @see MPU6050_INTERRUPT_DATA_RDY_BIT
01756  */
01757 void MPU6050::setIntDataReadyEnabled(bool enabled)
01758 {
01759     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled);
01760 }
01761 
01762 // INT_STATUS register
01763 
01764 /** Get full set of interrupt status bits.
01765  * These bits clear to 0 after the register has been read. Very useful
01766  * for getting multiple INT statuses, since each single bit read clears
01767  * all of them because it has to read the whole byte.
01768  * @return Current interrupt status
01769  * @see MPU6050_RA_INT_STATUS
01770  */
01771 uint8_t MPU6050::getIntStatus()
01772 {
01773     i2Cdev.readByte(devAddr, MPU6050_RA_INT_STATUS, buffer);
01774     return buffer[0];
01775 }
01776 /** Get Free Fall interrupt status.
01777  * This bit automatically sets to 1 when a Free Fall interrupt has been
01778  * generated. The bit clears to 0 after the register has been read.
01779  * @return Current interrupt status
01780  * @see MPU6050_RA_INT_STATUS
01781  * @see MPU6050_INTERRUPT_FF_BIT
01782  */
01783 bool MPU6050::getIntFreefallStatus()
01784 {
01785     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer);
01786     return buffer[0];
01787 }
01788 /** Get Motion Detection interrupt status.
01789  * This bit automatically sets to 1 when a Motion Detection interrupt has been
01790  * generated. The bit clears to 0 after the register has been read.
01791  * @return Current interrupt status
01792  * @see MPU6050_RA_INT_STATUS
01793  * @see MPU6050_INTERRUPT_MOT_BIT
01794  */
01795 bool MPU6050::getIntMotionStatus()
01796 {
01797     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer);
01798     return buffer[0];
01799 }
01800 /** Get Zero Motion Detection interrupt status.
01801  * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
01802  * been generated. The bit clears to 0 after the register has been read.
01803  * @return Current interrupt status
01804  * @see MPU6050_RA_INT_STATUS
01805  * @see MPU6050_INTERRUPT_ZMOT_BIT
01806  */
01807 bool MPU6050::getIntZeroMotionStatus()
01808 {
01809     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
01810     return buffer[0];
01811 }
01812 /** Get FIFO Buffer Overflow interrupt status.
01813  * This bit automatically sets to 1 when a Free Fall interrupt has been
01814  * generated. The bit clears to 0 after the register has been read.
01815  * @return Current interrupt status
01816  * @see MPU6050_RA_INT_STATUS
01817  * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
01818  */
01819 bool MPU6050::getIntFIFOBufferOverflowStatus()
01820 {
01821     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
01822     return buffer[0];
01823 }
01824 /** Get I2C Master interrupt status.
01825  * This bit automatically sets to 1 when an I2C Master interrupt has been
01826  * generated. For a list of I2C Master interrupts, please refer to Register 54.
01827  * The bit clears to 0 after the register has been read.
01828  * @return Current interrupt status
01829  * @see MPU6050_RA_INT_STATUS
01830  * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
01831  */
01832 bool MPU6050::getIntI2CMasterStatus()
01833 {
01834     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
01835     return buffer[0];
01836 }
01837 /** Get Data Ready interrupt status.
01838  * This bit automatically sets to 1 when a Data Ready interrupt has been
01839  * generated. The bit clears to 0 after the register has been read.
01840  * @return Current interrupt status
01841  * @see MPU6050_RA_INT_STATUS
01842  * @see MPU6050_INTERRUPT_DATA_RDY_BIT
01843  */
01844 bool MPU6050::getIntDataReadyStatus()
01845 {
01846     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
01847     return buffer[0];
01848 }
01849 
01850 // ACCEL_*OUT_* registers
01851 
01852 /** Get raw 9-axis motion sensor readings (accel/gyro/compass).
01853  * FUNCTION NOT FULLY IMPLEMENTED YET.
01854  * @param ax 16-bit signed integer container for accelerometer X-axis value
01855  * @param ay 16-bit signed integer container for accelerometer Y-axis value
01856  * @param az 16-bit signed integer container for accelerometer Z-axis value
01857  * @param gx 16-bit signed integer container for gyroscope X-axis value
01858  * @param gy 16-bit signed integer container for gyroscope Y-axis value
01859  * @param gz 16-bit signed integer container for gyroscope Z-axis value
01860  * @param mx 16-bit signed integer container for magnetometer X-axis value
01861  * @param my 16-bit signed integer container for magnetometer Y-axis value
01862  * @param mz 16-bit signed integer container for magnetometer Z-axis value
01863  * @see getMotion6()
01864  * @see getAcceleration()
01865  * @see getRotation()
01866  * @see MPU6050_RA_ACCEL_XOUT_H
01867  */
01868 void MPU6050::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)
01869 {
01870     getMotion6(ax, ay, az, gx, gy, gz);
01871     // TODO: magnetometer integration
01872 }
01873 /** Get raw 6-axis motion sensor readings (accel/gyro).
01874  * Retrieves all currently available motion sensor values.
01875  * @param ax 16-bit signed integer container for accelerometer X-axis value
01876  * @param ay 16-bit signed integer container for accelerometer Y-axis value
01877  * @param az 16-bit signed integer container for accelerometer Z-axis value
01878  * @param gx 16-bit signed integer container for gyroscope X-axis value
01879  * @param gy 16-bit signed integer container for gyroscope Y-axis value
01880  * @param gz 16-bit signed integer container for gyroscope Z-axis value
01881  * @see getAcceleration()
01882  * @see getRotation()
01883  * @see MPU6050_RA_ACCEL_XOUT_H
01884  */
01885 void MPU6050::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
01886 {
01887     i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer);
01888     *ax = (((int16_t)buffer[0]) << 8) | buffer[1];
01889     *ay = (((int16_t)buffer[2]) << 8) | buffer[3];
01890     *az = (((int16_t)buffer[4]) << 8) | buffer[5];
01891     *gx = (((int16_t)buffer[8]) << 8) | buffer[9];
01892     *gy = (((int16_t)buffer[10]) << 8) | buffer[11];
01893     *gz = (((int16_t)buffer[12]) << 8) | buffer[13];
01894 }
01895 /** Get 3-axis accelerometer readings.
01896  * These registers store the most recent accelerometer measurements.
01897  * Accelerometer measurements are written to these registers at the Sample Rate
01898  * as defined in Register 25.
01899  *
01900  * The accelerometer measurement registers, along with the temperature
01901  * measurement registers, gyroscope measurement registers, and external sensor
01902  * data registers, are composed of two sets of registers: an internal register
01903  * set and a user-facing read register set.
01904  *
01905  * The data within the accelerometer sensors' internal register set is always
01906  * updated at the Sample Rate. Meanwhile, the user-facing read register set
01907  * duplicates the internal register set's data values whenever the serial
01908  * interface is idle. This guarantees that a burst read of sensor registers will
01909  * read measurements from the same sampling instant. Note that if burst reads
01910  * are not used, the user is responsible for ensuring a set of single byte reads
01911  * correspond to a single sampling instant by checking the Data Ready interrupt.
01912  *
01913  * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
01914  * (Register 28). For each full scale setting, the accelerometers' sensitivity
01915  * per LSB in ACCEL_xOUT is shown in the table below:
01916  *
01917  * <pre>
01918  * AFS_SEL | Full Scale Range | LSB Sensitivity
01919  * --------+------------------+----------------
01920  * 0       | +/- 2g           | 8192 LSB/mg
01921  * 1       | +/- 4g           | 4096 LSB/mg
01922  * 2       | +/- 8g           | 2048 LSB/mg
01923  * 3       | +/- 16g          | 1024 LSB/mg
01924  * </pre>
01925  *
01926  * @param x 16-bit signed integer container for X-axis acceleration
01927  * @param y 16-bit signed integer container for Y-axis acceleration
01928  * @param z 16-bit signed integer container for Z-axis acceleration
01929  * @see MPU6050_RA_GYRO_XOUT_H
01930  */
01931 void MPU6050::getAcceleration(int16_t* x, int16_t* y, int16_t* z)
01932 {
01933     i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer);
01934     *x = (((int16_t)buffer[0]) << 8) | buffer[1];
01935     *y = (((int16_t)buffer[2]) << 8) | buffer[3];
01936     *z = (((int16_t)buffer[4]) << 8) | buffer[5];
01937 }
01938 /** Get X-axis accelerometer reading.
01939  * @return X-axis acceleration measurement in 16-bit 2's complement format
01940  * @see getMotion6()
01941  * @see MPU6050_RA_ACCEL_XOUT_H
01942  */
01943 int16_t MPU6050::getAccelerationX()
01944 {
01945     i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer);
01946     return (((int16_t)buffer[0]) << 8) | buffer[1];
01947 }
01948 /** Get Y-axis accelerometer reading.
01949  * @return Y-axis acceleration measurement in 16-bit 2's complement format
01950  * @see getMotion6()
01951  * @see MPU6050_RA_ACCEL_YOUT_H
01952  */
01953 int16_t MPU6050::getAccelerationY()
01954 {
01955     i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer);
01956     return (((int16_t)buffer[0]) << 8) | buffer[1];
01957 }
01958 /** Get Z-axis accelerometer reading.
01959  * @return Z-axis acceleration measurement in 16-bit 2's complement format
01960  * @see getMotion6()
01961  * @see MPU6050_RA_ACCEL_ZOUT_H
01962  */
01963 int16_t MPU6050::getAccelerationZ()
01964 {
01965     i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer);
01966     return (((int16_t)buffer[0]) << 8) | buffer[1];
01967 }
01968 
01969 // TEMP_OUT_* registers
01970 
01971 /** Get current internal temperature.
01972  * @return Temperature reading in 16-bit 2's complement format
01973  * @see MPU6050_RA_TEMP_OUT_H
01974  */
01975 int16_t MPU6050::getTemperature()
01976 {
01977     i2Cdev.readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer);
01978     return (((int16_t)buffer[0]) << 8) | buffer[1];
01979 }
01980 
01981 // GYRO_*OUT_* registers
01982 
01983 /** Get 3-axis gyroscope readings.
01984  * These gyroscope measurement registers, along with the accelerometer
01985  * measurement registers, temperature measurement registers, and external sensor
01986  * data registers, are composed of two sets of registers: an internal register
01987  * set and a user-facing read register set.
01988  * The data within the gyroscope sensors' internal register set is always
01989  * updated at the Sample Rate. Meanwhile, the user-facing read register set
01990  * duplicates the internal register set's data values whenever the serial
01991  * interface is idle. This guarantees that a burst read of sensor registers will
01992  * read measurements from the same sampling instant. Note that if burst reads
01993  * are not used, the user is responsible for ensuring a set of single byte reads
01994  * correspond to a single sampling instant by checking the Data Ready interrupt.
01995  *
01996  * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
01997  * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
01998  * LSB in GYRO_xOUT is shown in the table below:
01999  *
02000  * <pre>
02001  * FS_SEL | Full Scale Range   | LSB Sensitivity
02002  * -------+--------------------+----------------
02003  * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
02004  * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
02005  * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
02006  * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
02007  * </pre>
02008  *
02009  * @param x 16-bit signed integer container for X-axis rotation
02010  * @param y 16-bit signed integer container for Y-axis rotation
02011  * @param z 16-bit signed integer container for Z-axis rotation
02012  * @see getMotion6()
02013  * @see MPU6050_RA_GYRO_XOUT_H
02014  */
02015 void MPU6050::getRotation(int16_t* x, int16_t* y, int16_t* z)
02016 {
02017     i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer);
02018     *x = (((int16_t)buffer[0]) << 8) | buffer[1];
02019     *y = (((int16_t)buffer[2]) << 8) | buffer[3];
02020     *z = (((int16_t)buffer[4]) << 8) | buffer[5];
02021 }
02022 /** Get X-axis gyroscope reading.
02023  * @return X-axis rotation measurement in 16-bit 2's complement format
02024  * @see getMotion6()
02025  * @see MPU6050_RA_GYRO_XOUT_H
02026  */
02027 int16_t MPU6050::getRotationX()
02028 {
02029     i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer);
02030     return (((int16_t)buffer[0]) << 8) | buffer[1];
02031 }
02032 /** Get Y-axis gyroscope reading.
02033  * @return Y-axis rotation measurement in 16-bit 2's complement format
02034  * @see getMotion6()
02035  * @see MPU6050_RA_GYRO_YOUT_H
02036  */
02037 int16_t MPU6050::getRotationY()
02038 {
02039     i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer);
02040     return (((int16_t)buffer[0]) << 8) | buffer[1];
02041 }
02042 /** Get Z-axis gyroscope reading.
02043  * @return Z-axis rotation measurement in 16-bit 2's complement format
02044  * @see getMotion6()
02045  * @see MPU6050_RA_GYRO_ZOUT_H
02046  */
02047 int16_t MPU6050::getRotationZ()
02048 {
02049     i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer);
02050     return (((int16_t)buffer[0]) << 8) | buffer[1];
02051 }
02052 
02053 // EXT_SENS_DATA_* registers
02054 
02055 /** Read single byte from external sensor data register.
02056  * These registers store data read from external sensors by the Slave 0, 1, 2,
02057  * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
02058  * I2C_SLV4_DI (Register 53).
02059  *
02060  * External sensor data is written to these registers at the Sample Rate as
02061  * defined in Register 25. This access rate can be reduced by using the Slave
02062  * Delay Enable registers (Register 103).
02063  *
02064  * External sensor data registers, along with the gyroscope measurement
02065  * registers, accelerometer measurement registers, and temperature measurement
02066  * registers, are composed of two sets of registers: an internal register set
02067  * and a user-facing read register set.
02068  *
02069  * The data within the external sensors' internal register set is always updated
02070  * at the Sample Rate (or the reduced access rate) whenever the serial interface
02071  * is idle. This guarantees that a burst read of sensor registers will read
02072  * measurements from the same sampling instant. Note that if burst reads are not
02073  * used, the user is responsible for ensuring a set of single byte reads
02074  * correspond to a single sampling instant by checking the Data Ready interrupt.
02075  *
02076  * Data is placed in these external sensor data registers according to
02077  * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
02078  * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
02079  * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
02080  * defined in Register 25) or delayed rate (if specified in Register 52 and
02081  * 103). During each Sample cycle, slave reads are performed in order of Slave
02082  * number. If all slaves are enabled with more than zero bytes to be read, the
02083  * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
02084  *
02085  * Each enabled slave will have EXT_SENS_DATA registers associated with it by
02086  * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
02087  * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
02088  * change the higher numbered slaves' associated registers. Furthermore, if
02089  * fewer total bytes are being read from the external sensors as a result of
02090  * such a change, then the data remaining in the registers which no longer have
02091  * an associated slave device (i.e. high numbered registers) will remain in
02092  * these previously allocated registers unless reset.
02093  *
02094  * If the sum of the read lengths of all SLVx transactions exceed the number of
02095  * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
02096  * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
02097  * the slaves cannot be greater than 24 or some bytes will be lost.
02098  *
02099  * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
02100  * information regarding the characteristics of Slave 4, please refer to
02101  * Registers 49 to 53.
02102  *
02103  * EXAMPLE:
02104  * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
02105  * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
02106  * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
02107  * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
02108  * will be associated with Slave 1. If Slave 2 is enabled as well, registers
02109  * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
02110  *
02111  * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
02112  * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
02113  * instead.
02114  *
02115  * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
02116  * If a slave is disabled at any time, the space initially allocated to the
02117  * slave in the EXT_SENS_DATA register, will remain associated with that slave.
02118  * This is to avoid dynamic adjustment of the register allocation.
02119  *
02120  * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
02121  * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
02122  *
02123  * This above is also true if one of the slaves gets NACKed and stops
02124  * functioning.
02125  *
02126  * @param position Starting position (0-23)
02127  * @return Byte read from register
02128  */
02129 uint8_t MPU6050::getExternalSensorByte(int position)
02130 {
02131     i2Cdev.readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer);
02132     return buffer[0];
02133 }
02134 /** Read word (2 bytes) from external sensor data registers.
02135  * @param position Starting position (0-21)
02136  * @return Word read from register
02137  * @see getExternalSensorByte()
02138  */
02139 uint16_t MPU6050::getExternalSensorWord(int position)
02140 {
02141     i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer);
02142     return (((uint16_t)buffer[0]) << 8) | buffer[1];
02143 }
02144 /** Read double word (4 bytes) from external sensor data registers.
02145  * @param position Starting position (0-20)
02146  * @return Double word read from registers
02147  * @see getExternalSensorByte()
02148  */
02149 uint32_t MPU6050::getExternalSensorDWord(int position)
02150 {
02151     i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer);
02152     return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3];
02153 }
02154 
02155 // MOT_DETECT_STATUS register
02156 
02157 /** Get X-axis negative motion detection interrupt status.
02158  * @return Motion detection status
02159  * @see MPU6050_RA_MOT_DETECT_STATUS
02160  * @see MPU6050_MOTION_MOT_XNEG_BIT
02161  */
02162 bool MPU6050::getXNegMotionDetected()
02163 {
02164     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer);
02165     return buffer[0];
02166 }
02167 /** Get X-axis positive motion detection interrupt status.
02168  * @return Motion detection status
02169  * @see MPU6050_RA_MOT_DETECT_STATUS
02170  * @see MPU6050_MOTION_MOT_XPOS_BIT
02171  */
02172 bool MPU6050::getXPosMotionDetected()
02173 {
02174     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer);
02175     return buffer[0];
02176 }
02177 /** Get Y-axis negative motion detection interrupt status.
02178  * @return Motion detection status
02179  * @see MPU6050_RA_MOT_DETECT_STATUS
02180  * @see MPU6050_MOTION_MOT_YNEG_BIT
02181  */
02182 bool MPU6050::getYNegMotionDetected()
02183 {
02184     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer);
02185     return buffer[0];
02186 }
02187 /** Get Y-axis positive motion detection interrupt status.
02188  * @return Motion detection status
02189  * @see MPU6050_RA_MOT_DETECT_STATUS
02190  * @see MPU6050_MOTION_MOT_YPOS_BIT
02191  */
02192 bool MPU6050::getYPosMotionDetected()
02193 {
02194     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer);
02195     return buffer[0];
02196 }
02197 /** Get Z-axis negative motion detection interrupt status.
02198  * @return Motion detection status
02199  * @see MPU6050_RA_MOT_DETECT_STATUS
02200  * @see MPU6050_MOTION_MOT_ZNEG_BIT
02201  */
02202 bool MPU6050::getZNegMotionDetected()
02203 {
02204     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer);
02205     return buffer[0];
02206 }
02207 /** Get Z-axis positive motion detection interrupt status.
02208  * @return Motion detection status
02209  * @see MPU6050_RA_MOT_DETECT_STATUS
02210  * @see MPU6050_MOTION_MOT_ZPOS_BIT
02211  */
02212 bool MPU6050::getZPosMotionDetected()
02213 {
02214     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer);
02215     return buffer[0];
02216 }
02217 /** Get zero motion detection interrupt status.
02218  * @return Motion detection status
02219  * @see MPU6050_RA_MOT_DETECT_STATUS
02220  * @see MPU6050_MOTION_MOT_ZRMOT_BIT
02221  */
02222 bool MPU6050::getZeroMotionDetected()
02223 {
02224     i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer);
02225     return buffer[0];
02226 }
02227 
02228 // I2C_SLV*_DO register
02229 
02230 /** Write byte to Data Output container for specified slave.
02231  * This register holds the output data written into Slave when Slave is set to
02232  * write mode. For further information regarding Slave control, please
02233  * refer to Registers 37 to 39 and immediately following.
02234  * @param num Slave number (0-3)
02235  * @param data Byte to write
02236  * @see MPU6050_RA_I2C_SLV0_DO
02237  */
02238 void MPU6050::setSlaveOutputByte(uint8_t num, uint8_t data)
02239 {
02240     if (num > 3) return;
02241     i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data);
02242 }
02243 
02244 // I2C_MST_DELAY_CTRL register
02245 
02246 /** Get external data shadow delay enabled status.
02247  * This register is used to specify the timing of external sensor data
02248  * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
02249  * sensor data is delayed until all data has been received.
02250  * @return Current external data shadow delay enabled status.
02251  * @see MPU6050_RA_I2C_MST_DELAY_CTRL
02252  * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
02253  */
02254 bool MPU6050::getExternalShadowDelayEnabled()
02255 {
02256     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer);
02257     return buffer[0];
02258 }
02259 /** Set external data shadow delay enabled status.
02260  * @param enabled New external data shadow delay enabled status.
02261  * @see getExternalShadowDelayEnabled()
02262  * @see MPU6050_RA_I2C_MST_DELAY_CTRL
02263  * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
02264  */
02265 void MPU6050::setExternalShadowDelayEnabled(bool enabled)
02266 {
02267     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
02268 }
02269 /** Get slave delay enabled status.
02270  * When a particular slave delay is enabled, the rate of access for the that
02271  * slave device is reduced. When a slave's access rate is decreased relative to
02272  * the Sample Rate, the slave is accessed every:
02273  *
02274  *     1 / (1 + I2C_MST_DLY) Samples
02275  *
02276  * This base Sample Rate in turn is determined by SMPLRT_DIV (register  * 25)
02277  * and DLPF_CFG (register 26).
02278  *
02279  * For further information regarding I2C_MST_DLY, please refer to register 52.
02280  * For further information regarding the Sample Rate, please refer to register 25.
02281  *
02282  * @param num Slave number (0-4)
02283  * @return Current slave delay enabled status.
02284  * @see MPU6050_RA_I2C_MST_DELAY_CTRL
02285  * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
02286  */
02287 bool MPU6050::getSlaveDelayEnabled(uint8_t num)
02288 {
02289     // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
02290     if (num > 4) return 0;
02291     i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer);
02292     return buffer[0];
02293 }
02294 /** Set slave delay enabled status.
02295  * @param num Slave number (0-4)
02296  * @param enabled New slave delay enabled status.
02297  * @see MPU6050_RA_I2C_MST_DELAY_CTRL
02298  * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
02299  */
02300 void MPU6050::setSlaveDelayEnabled(uint8_t num, bool enabled)
02301 {
02302     i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled);
02303 }
02304 
02305 // SIGNAL_PATH_RESET register
02306 
02307 /** Reset gyroscope signal path.
02308  * The reset will revert the signal path analog to digital converters and
02309  * filters to their power up configurations.
02310  * @see MPU6050_RA_SIGNAL_PATH_RESET
02311  * @see MPU6050_PATHRESET_GYRO_RESET_BIT
02312  */
02313 void MPU6050::resetGyroscopePath()
02314 {
02315     i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true);
02316 }
02317 /** Reset accelerometer signal path.
02318  * The reset will revert the signal path analog to digital converters and
02319  * filters to their power up configurations.
02320  * @see MPU6050_RA_SIGNAL_PATH_RESET
02321  * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
02322  */
02323 void MPU6050::resetAccelerometerPath()
02324 {
02325     i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true);
02326 }
02327 /** Reset temperature sensor signal path.
02328  * The reset will revert the signal path analog to digital converters and
02329  * filters to their power up configurations.
02330  * @see MPU6050_RA_SIGNAL_PATH_RESET
02331  * @see MPU6050_PATHRESET_TEMP_RESET_BIT
02332  */
02333 void MPU6050::resetTemperaturePath()
02334 {
02335     i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true);
02336 }
02337 
02338 // MOT_DETECT_CTRL register
02339 
02340 /** Get accelerometer power-on delay.
02341  * The accelerometer data path provides samples to the sensor registers, Motion
02342  * detection, Zero Motion detection, and Free Fall detection modules. The
02343  * signal path contains filters which must be flushed on wake-up with new
02344  * samples before the detection modules begin operations. The default wake-up
02345  * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
02346  * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
02347  * any value above zero unless instructed otherwise by InvenSense. Please refer
02348  * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
02349  * further information regarding the detection modules.
02350  * @return Current accelerometer power-on delay
02351  * @see MPU6050_RA_MOT_DETECT_CTRL
02352  * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
02353  */
02354 uint8_t MPU6050::getAccelerometerPowerOnDelay()
02355 {
02356     i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
02357     return buffer[0];
02358 }
02359 /** Set accelerometer power-on delay.
02360  * @param delay New accelerometer power-on delay (0-3)
02361  * @see getAccelerometerPowerOnDelay()
02362  * @see MPU6050_RA_MOT_DETECT_CTRL
02363  * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
02364  */
02365 void MPU6050::setAccelerometerPowerOnDelay(uint8_t delay)
02366 {
02367     i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
02368 }
02369 /** Get Free Fall detection counter decrement configuration.
02370  * Detection is registered by the Free Fall detection module after accelerometer
02371  * measurements meet their respective threshold conditions over a specified
02372  * number of samples. When the threshold conditions are met, the corresponding
02373  * detection counter increments by 1. The user may control the rate at which the
02374  * detection counter decrements when the threshold condition is not met by
02375  * configuring FF_COUNT. The decrement rate can be set according to the
02376  * following table:
02377  *
02378  * <pre>
02379  * FF_COUNT | Counter Decrement
02380  * ---------+------------------
02381  * 0        | Reset
02382  * 1        | 1
02383  * 2        | 2
02384  * 3        | 4
02385  * </pre>
02386  *
02387  * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
02388  * reset the counter to 0. For further information on Free Fall detection,
02389  * please refer to Registers 29 to 32.
02390  *
02391  * @return Current decrement configuration
02392  * @see MPU6050_RA_MOT_DETECT_CTRL
02393  * @see MPU6050_DETECT_FF_COUNT_BIT
02394  */
02395 uint8_t MPU6050::getFreefallDetectionCounterDecrement()
02396 {
02397     i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer);
02398     return buffer[0];
02399 }
02400 /** Set Free Fall detection counter decrement configuration.
02401  * @param decrement New decrement configuration value
02402  * @see getFreefallDetectionCounterDecrement()
02403  * @see MPU6050_RA_MOT_DETECT_CTRL
02404  * @see MPU6050_DETECT_FF_COUNT_BIT
02405  */
02406 void MPU6050::setFreefallDetectionCounterDecrement(uint8_t decrement)
02407 {
02408     i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement);
02409 }
02410 /** Get Motion detection counter decrement configuration.
02411  * Detection is registered by the Motion detection module after accelerometer
02412  * measurements meet their respective threshold conditions over a specified
02413  * number of samples. When the threshold conditions are met, the corresponding
02414  * detection counter increments by 1. The user may control the rate at which the
02415  * detection counter decrements when the threshold condition is not met by
02416  * configuring MOT_COUNT. The decrement rate can be set according to the
02417  * following table:
02418  *
02419  * <pre>
02420  * MOT_COUNT | Counter Decrement
02421  * ----------+------------------
02422  * 0         | Reset
02423  * 1         | 1
02424  * 2         | 2
02425  * 3         | 4
02426  * </pre>
02427  *
02428  * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
02429  * reset the counter to 0. For further information on Motion detection,
02430  * please refer to Registers 29 to 32.
02431  *
02432  */
02433 uint8_t MPU6050::getMotionDetectionCounterDecrement()
02434 {
02435     i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer);
02436     return buffer[0];
02437 }
02438 /** Set Motion detection counter decrement configuration.
02439  * @param decrement New decrement configuration value
02440  * @see getMotionDetectionCounterDecrement()
02441  * @see MPU6050_RA_MOT_DETECT_CTRL
02442  * @see MPU6050_DETECT_MOT_COUNT_BIT
02443  */
02444 void MPU6050::setMotionDetectionCounterDecrement(uint8_t decrement)
02445 {
02446     i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement);
02447 }
02448 
02449 // USER_CTRL register
02450 
02451 /** Get FIFO enabled status.
02452  * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
02453  * cannot be written to or read from while disabled. The FIFO buffer's state
02454  * does not change unless the MPU-60X0 is power cycled.
02455  * @return Current FIFO enabled status
02456  * @see MPU6050_RA_USER_CTRL
02457  * @see MPU6050_USERCTRL_FIFO_EN_BIT
02458  */
02459 bool MPU6050::getFIFOEnabled()
02460 {
02461     i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer);
02462     return buffer[0];
02463 }
02464 /** Set FIFO enabled status.
02465  * @param enabled New FIFO enabled status
02466  * @see getFIFOEnabled()
02467  * @see MPU6050_RA_USER_CTRL
02468  * @see MPU6050_USERCTRL_FIFO_EN_BIT
02469  */
02470 void MPU6050::setFIFOEnabled(bool enabled)
02471 {
02472     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled);
02473 }
02474 /** Get I2C Master Mode enabled status.
02475  * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
02476  * external sensor slave devices on the auxiliary I2C bus. When this bit is
02477  * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
02478  * driven by the primary I2C bus (SDA and SCL). This is a precondition to
02479  * enabling Bypass Mode. For further information regarding Bypass Mode, please
02480  * refer to Register 55.
02481  * @return Current I2C Master Mode enabled status
02482  * @see MPU6050_RA_USER_CTRL
02483  * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
02484  */
02485 bool MPU6050::getI2CMasterModeEnabled()
02486 {
02487     i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer);
02488     return buffer[0];
02489 }
02490 /** Set I2C Master Mode enabled status.
02491  * @param enabled New I2C Master Mode enabled status
02492  * @see getI2CMasterModeEnabled()
02493  * @see MPU6050_RA_USER_CTRL
02494  * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
02495  */
02496 void MPU6050::setI2CMasterModeEnabled(bool enabled)
02497 {
02498     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled);
02499 }
02500 /** Switch from I2C to SPI mode (MPU-6000 only)
02501  * If this is set, the primary SPI interface will be enabled in place of the
02502  * disabled primary I2C interface.
02503  */
02504 void MPU6050::switchSPIEnabled(bool enabled)
02505 {
02506     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled);
02507 }
02508 /** Reset the FIFO.
02509  * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
02510  * bit automatically clears to 0 after the reset has been triggered.
02511  * @see MPU6050_RA_USER_CTRL
02512  * @see MPU6050_USERCTRL_FIFO_RESET_BIT
02513  */
02514 void MPU6050::resetFIFO()
02515 {
02516     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true);
02517 }
02518 /** Reset the I2C Master.
02519  * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
02520  * This bit automatically clears to 0 after the reset has been triggered.
02521  * @see MPU6050_RA_USER_CTRL
02522  * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
02523  */
02524 void MPU6050::resetI2CMaster()
02525 {
02526     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true);
02527 }
02528 /** Reset all sensor registers and signal paths.
02529  * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
02530  * accelerometers, and temperature sensor). This operation will also clear the
02531  * sensor registers. This bit automatically clears to 0 after the reset has been
02532  * triggered.
02533  *
02534  * When resetting only the signal path (and not the sensor registers), please
02535  * use Register 104, SIGNAL_PATH_RESET.
02536  *
02537  * @see MPU6050_RA_USER_CTRL
02538  * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
02539  */
02540 void MPU6050::resetSensors()
02541 {
02542     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true);
02543 }
02544 
02545 // PWR_MGMT_1 register
02546 
02547 /** Trigger a full device reset.
02548  * A small delay of ~50ms may be desirable after triggering a reset.
02549  * @see MPU6050_RA_PWR_MGMT_1
02550  * @see MPU6050_PWR1_DEVICE_RESET_BIT
02551  */
02552 void MPU6050::reset()
02553 {
02554     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true);
02555 }
02556 /** Get sleep mode status.
02557  * Setting the SLEEP bit in the register puts the device into very low power
02558  * sleep mode. In this mode, only the serial interface and internal registers
02559  * remain active, allowing for a very low standby current. Clearing this bit
02560  * puts the device back into normal mode. To save power, the individual standby
02561  * selections for each of the gyros should be used if any gyro axis is not used
02562  * by the application.
02563  * @return Current sleep mode enabled status
02564  * @see MPU6050_RA_PWR_MGMT_1
02565  * @see MPU6050_PWR1_SLEEP_BIT
02566  */
02567 bool MPU6050::getSleepEnabled()
02568 {
02569     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer);
02570     return buffer[0];
02571 }
02572 /** Set sleep mode status.
02573  * @param enabled New sleep mode enabled status
02574  * @see getSleepEnabled()
02575  * @see MPU6050_RA_PWR_MGMT_1
02576  * @see MPU6050_PWR1_SLEEP_BIT
02577  */
02578 void MPU6050::setSleepEnabled(bool enabled)
02579 {
02580     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled);
02581 }
02582 /** Get wake cycle enabled status.
02583  * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
02584  * between sleep mode and waking up to take a single sample of data from active
02585  * sensors at a rate determined by LP_WAKE_CTRL (register 108).
02586  * @return Current sleep mode enabled status
02587  * @see MPU6050_RA_PWR_MGMT_1
02588  * @see MPU6050_PWR1_CYCLE_BIT
02589  */
02590 bool MPU6050::getWakeCycleEnabled()
02591 {
02592     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer);
02593     return buffer[0];
02594 }
02595 /** Set wake cycle enabled status.
02596  * @param enabled New sleep mode enabled status
02597  * @see getWakeCycleEnabled()
02598  * @see MPU6050_RA_PWR_MGMT_1
02599  * @see MPU6050_PWR1_CYCLE_BIT
02600  */
02601 void MPU6050::setWakeCycleEnabled(bool enabled)
02602 {
02603     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled);
02604 }
02605 /** Get temperature sensor enabled status.
02606  * Control the usage of the internal temperature sensor.
02607  *
02608  * Note: this register stores the *disabled* value, but for consistency with the
02609  * rest of the code, the function is named and used with standard true/false
02610  * values to indicate whether the sensor is enabled or disabled, respectively.
02611  *
02612  * @return Current temperature sensor enabled status
02613  * @see MPU6050_RA_PWR_MGMT_1
02614  * @see MPU6050_PWR1_TEMP_DIS_BIT
02615  */
02616 bool MPU6050::getTempSensorEnabled()
02617 {
02618     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer);
02619     return buffer[0] == 0; // 1 is actually disabled here
02620 }
02621 /** Set temperature sensor enabled status.
02622  * Note: this register stores the *disabled* value, but for consistency with the
02623  * rest of the code, the function is named and used with standard true/false
02624  * values to indicate whether the sensor is enabled or disabled, respectively.
02625  *
02626  * @param enabled New temperature sensor enabled status
02627  * @see getTempSensorEnabled()
02628  * @see MPU6050_RA_PWR_MGMT_1
02629  * @see MPU6050_PWR1_TEMP_DIS_BIT
02630  */
02631 void MPU6050::setTempSensorEnabled(bool enabled)
02632 {
02633     // 1 is actually disabled here
02634     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled);
02635 }
02636 /** Get clock source setting.
02637  * @return Current clock source setting
02638  * @see MPU6050_RA_PWR_MGMT_1
02639  * @see MPU6050_PWR1_CLKSEL_BIT
02640  * @see MPU6050_PWR1_CLKSEL_LENGTH
02641  */
02642 uint8_t MPU6050::getClockSource()
02643 {
02644     i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer);
02645     return buffer[0];
02646 }
02647 /** Set clock source setting.
02648  * An internal 8MHz oscillator, gyroscope based clock, or external sources can
02649  * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
02650  * or an external source is chosen as the clock source, the MPU-60X0 can operate
02651  * in low power modes with the gyroscopes disabled.
02652  *
02653  * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
02654  * However, it is highly recommended that the device be configured to use one of
02655  * the gyroscopes (or an external clock source) as the clock reference for
02656  * improved stability. The clock source can be selected according to the following table:
02657  *
02658  * <pre>
02659  * CLK_SEL | Clock Source
02660  * --------+--------------------------------------
02661  * 0       | Internal oscillator
02662  * 1       | PLL with X Gyro reference
02663  * 2       | PLL with Y Gyro reference
02664  * 3       | PLL with Z Gyro reference
02665  * 4       | PLL with external 32.768kHz reference
02666  * 5       | PLL with external 19.2MHz reference
02667  * 6       | Reserved
02668  * 7       | Stops the clock and keeps the timing generator in reset
02669  * </pre>
02670  *
02671  * @param source New clock source setting
02672  * @see getClockSource()
02673  * @see MPU6050_RA_PWR_MGMT_1
02674  * @see MPU6050_PWR1_CLKSEL_BIT
02675  * @see MPU6050_PWR1_CLKSEL_LENGTH
02676  */
02677 void MPU6050::setClockSource(uint8_t source)
02678 {
02679     i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source);
02680 }
02681 
02682 // PWR_MGMT_2 register
02683 
02684 /** Get wake frequency in Accel-Only Low Power Mode.
02685  * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
02686  * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
02687  * the device will power off all devices except for the primary I2C interface,
02688  * waking only the accelerometer at fixed intervals to take a single
02689  * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
02690  * as shown below:
02691  *
02692  * <pre>
02693  * LP_WAKE_CTRL | Wake-up Frequency
02694  * -------------+------------------
02695  * 0            | 1.25 Hz
02696  * 1            | 2.5 Hz
02697  * 2            | 5 Hz
02698  * 3            | 10 Hz
02699  * <pre>
02700  *
02701  * For further information regarding the MPU-60X0's power modes, please refer to
02702  * Register 107.
02703  *
02704  * @return Current wake frequency
02705  * @see MPU6050_RA_PWR_MGMT_2
02706  */
02707 uint8_t MPU6050::getWakeFrequency()
02708 {
02709     i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
02710     return buffer[0];
02711 }
02712 /** Set wake frequency in Accel-Only Low Power Mode.
02713  * @param frequency New wake frequency
02714  * @see MPU6050_RA_PWR_MGMT_2
02715  */
02716 void MPU6050::setWakeFrequency(uint8_t frequency)
02717 {
02718     i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
02719 }
02720 
02721 /** Get X-axis accelerometer standby enabled status.
02722  * If enabled, the X-axis will not gather or report data (or use power).
02723  * @return Current X-axis standby enabled status
02724  * @see MPU6050_RA_PWR_MGMT_2
02725  * @see MPU6050_PWR2_STBY_XA_BIT
02726  */
02727 bool MPU6050::getStandbyXAccelEnabled()
02728 {
02729     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer);
02730     return buffer[0];
02731 }
02732 /** Set X-axis accelerometer standby enabled status.
02733  * @param New X-axis standby enabled status
02734  * @see getStandbyXAccelEnabled()
02735  * @see MPU6050_RA_PWR_MGMT_2
02736  * @see MPU6050_PWR2_STBY_XA_BIT
02737  */
02738 void MPU6050::setStandbyXAccelEnabled(bool enabled)
02739 {
02740     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled);
02741 }
02742 /** Get Y-axis accelerometer standby enabled status.
02743  * If enabled, the Y-axis will not gather or report data (or use power).
02744  * @return Current Y-axis standby enabled status
02745  * @see MPU6050_RA_PWR_MGMT_2
02746  * @see MPU6050_PWR2_STBY_YA_BIT
02747  */
02748 bool MPU6050::getStandbyYAccelEnabled()
02749 {
02750     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer);
02751     return buffer[0];
02752 }
02753 /** Set Y-axis accelerometer standby enabled status.
02754  * @param New Y-axis standby enabled status
02755  * @see getStandbyYAccelEnabled()
02756  * @see MPU6050_RA_PWR_MGMT_2
02757  * @see MPU6050_PWR2_STBY_YA_BIT
02758  */
02759 void MPU6050::setStandbyYAccelEnabled(bool enabled)
02760 {
02761     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled);
02762 }
02763 /** Get Z-axis accelerometer standby enabled status.
02764  * If enabled, the Z-axis will not gather or report data (or use power).
02765  * @return Current Z-axis standby enabled status
02766  * @see MPU6050_RA_PWR_MGMT_2
02767  * @see MPU6050_PWR2_STBY_ZA_BIT
02768  */
02769 bool MPU6050::getStandbyZAccelEnabled()
02770 {
02771     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer);
02772     return buffer[0];
02773 }
02774 /** Set Z-axis accelerometer standby enabled status.
02775  * @param New Z-axis standby enabled status
02776  * @see getStandbyZAccelEnabled()
02777  * @see MPU6050_RA_PWR_MGMT_2
02778  * @see MPU6050_PWR2_STBY_ZA_BIT
02779  */
02780 void MPU6050::setStandbyZAccelEnabled(bool enabled)
02781 {
02782     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled);
02783 }
02784 /** Get X-axis gyroscope standby enabled status.
02785  * If enabled, the X-axis will not gather or report data (or use power).
02786  * @return Current X-axis standby enabled status
02787  * @see MPU6050_RA_PWR_MGMT_2
02788  * @see MPU6050_PWR2_STBY_XG_BIT
02789  */
02790 bool MPU6050::getStandbyXGyroEnabled()
02791 {
02792     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer);
02793     return buffer[0];
02794 }
02795 /** Set X-axis gyroscope standby enabled status.
02796  * @param New X-axis standby enabled status
02797  * @see getStandbyXGyroEnabled()
02798  * @see MPU6050_RA_PWR_MGMT_2
02799  * @see MPU6050_PWR2_STBY_XG_BIT
02800  */
02801 void MPU6050::setStandbyXGyroEnabled(bool enabled)
02802 {
02803     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled);
02804 }
02805 /** Get Y-axis gyroscope standby enabled status.
02806  * If enabled, the Y-axis will not gather or report data (or use power).
02807  * @return Current Y-axis standby enabled status
02808  * @see MPU6050_RA_PWR_MGMT_2
02809  * @see MPU6050_PWR2_STBY_YG_BIT
02810  */
02811 bool MPU6050::getStandbyYGyroEnabled()
02812 {
02813     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer);
02814     return buffer[0];
02815 }
02816 /** Set Y-axis gyroscope standby enabled status.
02817  * @param New Y-axis standby enabled status
02818  * @see getStandbyYGyroEnabled()
02819  * @see MPU6050_RA_PWR_MGMT_2
02820  * @see MPU6050_PWR2_STBY_YG_BIT
02821  */
02822 void MPU6050::setStandbyYGyroEnabled(bool enabled)
02823 {
02824     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled);
02825 }
02826 /** Get Z-axis gyroscope standby enabled status.
02827  * If enabled, the Z-axis will not gather or report data (or use power).
02828  * @return Current Z-axis standby enabled status
02829  * @see MPU6050_RA_PWR_MGMT_2
02830  * @see MPU6050_PWR2_STBY_ZG_BIT
02831  */
02832 bool MPU6050::getStandbyZGyroEnabled()
02833 {
02834     i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer);
02835     return buffer[0];
02836 }
02837 /** Set Z-axis gyroscope standby enabled status.
02838  * @param New Z-axis standby enabled status
02839  * @see getStandbyZGyroEnabled()
02840  * @see MPU6050_RA_PWR_MGMT_2
02841  * @see MPU6050_PWR2_STBY_ZG_BIT
02842  */
02843 void MPU6050::setStandbyZGyroEnabled(bool enabled)
02844 {
02845     i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
02846 }
02847 
02848 // FIFO_COUNT* registers
02849 
02850 /** Get current FIFO buffer size.
02851  * This value indicates the number of bytes stored in the FIFO buffer. This
02852  * number is in turn the number of bytes that can be read from the FIFO buffer
02853  * and it is directly proportional to the number of samples available given the
02854  * set of sensor data bound to be stored in the FIFO (register 35 and 36).
02855  * @return Current FIFO buffer size
02856  */
02857 uint16_t MPU6050::getFIFOCount()
02858 {
02859     i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer);
02860     return (((uint16_t)buffer[0]) << 8) | buffer[1];
02861 }
02862 
02863 // FIFO_R_W register
02864 
02865 /** Get byte from FIFO buffer.
02866  * This register is used to read and write data from the FIFO buffer. Data is
02867  * written to the FIFO in order of register number (from lowest to highest). If
02868  * all the FIFO enable flags (see below) are enabled and all External Sensor
02869  * Data registers (Registers 73 to 96) are associated with a Slave device, the
02870  * contents of registers 59 through 96 will be written in order at the Sample
02871  * Rate.
02872  *
02873  * The contents of the sensor data registers (Registers 59 to 96) are written
02874  * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
02875  * in FIFO_EN (Register 35). An additional flag for the sensor data registers
02876  * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
02877  *
02878  * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
02879  * automatically set to 1. This bit is located in INT_STATUS (Register 58).
02880  * When the FIFO buffer has overflowed, the oldest data will be lost and new
02881  * data will be written to the FIFO.
02882  *
02883  * If the FIFO buffer is empty, reading this register will return the last byte
02884  * that was previously read from the FIFO until new data is available. The user
02885  * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
02886  * empty.
02887  *
02888  * @return Byte from FIFO buffer
02889  */
02890 uint8_t MPU6050::getFIFOByte()
02891 {
02892     i2Cdev.readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer);
02893     return buffer[0];
02894 }
02895 void MPU6050::getFIFOBytes(uint8_t *data, uint8_t length)
02896 {
02897     i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data);
02898 }
02899 /** Write byte to FIFO buffer.
02900  * @see getFIFOByte()
02901  * @see MPU6050_RA_FIFO_R_W
02902  */
02903 void MPU6050::setFIFOByte(uint8_t data)
02904 {
02905     i2Cdev.writeByte(devAddr, MPU6050_RA_FIFO_R_W, data);
02906 }
02907 
02908 // WHO_AM_I register
02909 
02910 /** Get Device ID.
02911  * This register is used to verify the identity of the device (0b110100, 0x34).
02912  * @return Device ID (6 bits only! should be 0x34)
02913  * @see MPU6050_RA_WHO_AM_I
02914  * @see MPU6050_WHO_AM_I_BIT
02915  * @see MPU6050_WHO_AM_I_LENGTH
02916  */
02917 uint8_t MPU6050::getDeviceID()
02918 {
02919     i2Cdev.readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer);
02920     return buffer[0];
02921 }
02922 /** Set Device ID.
02923  * Write a new ID into the WHO_AM_I register (no idea why this should ever be
02924  * necessary though).
02925  * @param id New device ID to set.
02926  * @see getDeviceID()
02927  * @see MPU6050_RA_WHO_AM_I
02928  * @see MPU6050_WHO_AM_I_BIT
02929  * @see MPU6050_WHO_AM_I_LENGTH
02930  */
02931 void MPU6050::setDeviceID(uint8_t id)
02932 {
02933     i2Cdev.writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id);
02934 }
02935 
02936 // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
02937 
02938 // XG_OFFS_TC register
02939 
02940 uint8_t MPU6050::getOTPBankValid()
02941 {
02942     i2Cdev.readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer);
02943     return buffer[0];
02944 }
02945 void MPU6050::setOTPBankValid(bool enabled)
02946 {
02947     i2Cdev.writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
02948 }
02949 int8_t MPU6050::getXGyroOffset()
02950 {
02951     i2Cdev.readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
02952     return buffer[0];
02953 }
02954 void MPU6050::setXGyroOffset(int8_t offset)
02955 {
02956     i2Cdev.writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
02957 }
02958 
02959 // YG_OFFS_TC register
02960 
02961 int8_t MPU6050::getYGyroOffset()
02962 {
02963     i2Cdev.readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
02964     return buffer[0];
02965 }
02966 void MPU6050::setYGyroOffset(int8_t offset)
02967 {
02968     i2Cdev.writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
02969 }
02970 
02971 // ZG_OFFS_TC register
02972 
02973 int8_t MPU6050::getZGyroOffset()
02974 {
02975     i2Cdev.readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
02976     return buffer[0];
02977 }
02978 void MPU6050::setZGyroOffset(int8_t offset)
02979 {
02980     i2Cdev.writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
02981 }
02982 
02983 // X_FINE_GAIN register
02984 
02985 int8_t MPU6050::getXFineGain()
02986 {
02987     i2Cdev.readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer);
02988     return buffer[0];
02989 }
02990 void MPU6050::setXFineGain(int8_t gain)
02991 {
02992     i2Cdev.writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain);
02993 }
02994 
02995 // Y_FINE_GAIN register
02996 
02997 int8_t MPU6050::getYFineGain()
02998 {
02999     i2Cdev.readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer);
03000     return buffer[0];
03001 }
03002 void MPU6050::setYFineGain(int8_t gain)
03003 {
03004     i2Cdev.writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
03005 }
03006 
03007 // Z_FINE_GAIN register
03008 
03009 int8_t MPU6050::getZFineGain()
03010 {
03011     i2Cdev.readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer);
03012     return buffer[0];
03013 }
03014 void MPU6050::setZFineGain(int8_t gain)
03015 {
03016     i2Cdev.writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
03017 }
03018 
03019 // XA_OFFS_* registers
03020 
03021 int16_t MPU6050::getXAccelOffset()
03022 {
03023     i2Cdev.readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer);
03024     return (((int16_t)buffer[0]) << 8) | buffer[1];
03025 }
03026 void MPU6050::setXAccelOffset(int16_t offset)
03027 {
03028     i2Cdev.writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset);
03029 }
03030 
03031 // YA_OFFS_* register
03032 
03033 int16_t MPU6050::getYAccelOffset()
03034 {
03035     i2Cdev.readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer);
03036     return (((int16_t)buffer[0]) << 8) | buffer[1];
03037 }
03038 void MPU6050::setYAccelOffset(int16_t offset)
03039 {
03040     i2Cdev.writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset);
03041 }
03042 
03043 // ZA_OFFS_* register
03044 
03045 int16_t MPU6050::getZAccelOffset()
03046 {
03047     i2Cdev.readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer);
03048     return (((int16_t)buffer[0]) << 8) | buffer[1];
03049 }
03050 void MPU6050::setZAccelOffset(int16_t offset)
03051 {
03052     i2Cdev.writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset);
03053 }
03054 
03055 // XG_OFFS_USR* registers
03056 
03057 int16_t MPU6050::getXGyroOffsetUser()
03058 {
03059     i2Cdev.readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer);
03060     return (((int16_t)buffer[0]) << 8) | buffer[1];
03061 }
03062 void MPU6050::setXGyroOffsetUser(int16_t offset)
03063 {
03064     i2Cdev.writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
03065 }
03066 
03067 // YG_OFFS_USR* register
03068 
03069 int16_t MPU6050::getYGyroOffsetUser()
03070 {
03071     i2Cdev.readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer);
03072     return (((int16_t)buffer[0]) << 8) | buffer[1];
03073 }
03074 void MPU6050::setYGyroOffsetUser(int16_t offset)
03075 {
03076     i2Cdev.writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
03077 }
03078 
03079 // ZG_OFFS_USR* register
03080 
03081 int16_t MPU6050::getZGyroOffsetUser()
03082 {
03083     i2Cdev.readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer);
03084     return (((int16_t)buffer[0]) << 8) | buffer[1];
03085 }
03086 void MPU6050::setZGyroOffsetUser(int16_t offset)
03087 {
03088     i2Cdev.writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
03089 }
03090 
03091 // INT_ENABLE register (DMP functions)
03092 
03093 bool MPU6050::getIntPLLReadyEnabled()
03094 {
03095     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
03096     return buffer[0];
03097 }
03098 void MPU6050::setIntPLLReadyEnabled(bool enabled)
03099 {
03100     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
03101 }
03102 bool MPU6050::getIntDMPEnabled()
03103 {
03104     i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
03105     return buffer[0];
03106 }
03107 void MPU6050::setIntDMPEnabled(bool enabled)
03108 {
03109     i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
03110 }
03111 
03112 // DMP_INT_STATUS
03113 
03114 bool MPU6050::getDMPInt5Status()
03115 {
03116     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer);
03117     return buffer[0];
03118 }
03119 bool MPU6050::getDMPInt4Status()
03120 {
03121     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer);
03122     return buffer[0];
03123 }
03124 bool MPU6050::getDMPInt3Status()
03125 {
03126     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer);
03127     return buffer[0];
03128 }
03129 bool MPU6050::getDMPInt2Status()
03130 {
03131     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer);
03132     return buffer[0];
03133 }
03134 bool MPU6050::getDMPInt1Status()
03135 {
03136     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer);
03137     return buffer[0];
03138 }
03139 bool MPU6050::getDMPInt0Status()
03140 {
03141     i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer);
03142     return buffer[0];
03143 }
03144 
03145 // INT_STATUS register (DMP functions)
03146 
03147 bool MPU6050::getIntPLLReadyStatus()
03148 {
03149     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
03150     return buffer[0];
03151 }
03152 bool MPU6050::getIntDMPStatus()
03153 {
03154     i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
03155     return buffer[0];
03156 }
03157 
03158 // USER_CTRL register (DMP functions)
03159 
03160 bool MPU6050::getDMPEnabled()
03161 {
03162     i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer);
03163     return buffer[0];
03164 }
03165 void MPU6050::setDMPEnabled(bool enabled)
03166 {
03167     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
03168 }
03169 void MPU6050::resetDMP()
03170 {
03171     i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true);
03172 }
03173 
03174 // BANK_SEL register
03175 
03176 void MPU6050::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
03177 {
03178     bank &= 0x1F;
03179     if (userBank) bank |= 0x20;
03180     if (prefetchEnabled) bank |= 0x40;
03181     i2Cdev.writeByte(devAddr, MPU6050_RA_BANK_SEL, bank);
03182 }
03183 
03184 // MEM_START_ADDR register
03185 
03186 void MPU6050::setMemoryStartAddress(uint8_t address)
03187 {
03188     i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address);
03189 }
03190 
03191 // MEM_R_W register
03192 
03193 uint8_t MPU6050::readMemoryByte()
03194 {
03195     i2Cdev.readByte(devAddr, MPU6050_RA_MEM_R_W, buffer);
03196     return buffer[0];
03197 }
03198 void MPU6050::writeMemoryByte(uint8_t data)
03199 {
03200     i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_R_W, data);
03201 }
03202 void MPU6050::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
03203 {
03204     setMemoryBank(bank);
03205     setMemoryStartAddress(address);
03206     uint8_t chunkSize;
03207     for (uint16_t i = 0; i < dataSize;) {
03208         // determine correct chunk size according to bank position and data size
03209         chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
03210 
03211         // make sure we don't go past the data size
03212         if (i + chunkSize > dataSize) chunkSize = dataSize - i;
03213 
03214         // make sure this chunk doesn't go past the bank boundary (256 bytes)
03215         if (chunkSize > 256 - address) chunkSize = 256 - address;
03216 
03217         // read the chunk of data as specified
03218         i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i);
03219 
03220         // increase byte index by [chunkSize]
03221         i += chunkSize;
03222 
03223         // uint8_t automatically wraps to 0 at 256
03224         address += chunkSize;
03225 
03226         // if we aren't done, update bank (if necessary) and address
03227         if (i < dataSize) {
03228             if (address == 0) bank++;
03229             setMemoryBank(bank);
03230             setMemoryStartAddress(address);
03231         }
03232     }
03233 }
03234 bool MPU6050::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem)
03235 {
03236     setMemoryBank(bank);
03237     setMemoryStartAddress(address);
03238     uint8_t chunkSize;
03239     uint8_t *verifyBuffer;
03240     uint8_t *progBuffer;
03241     uint16_t i;
03242     uint8_t j;
03243     if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
03244     if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
03245     for (i = 0; i < dataSize;) {
03246         // determine correct chunk size according to bank position and data size
03247         chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
03248 
03249         // make sure we don't go past the data size
03250         if (i + chunkSize > dataSize) chunkSize = dataSize - i;
03251 
03252         // make sure this chunk doesn't go past the bank boundary (256 bytes)
03253         if (chunkSize > 256 - address) chunkSize = 256 - address;
03254 
03255         if (useProgMem) {
03256             // write the chunk of data as specified
03257             for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
03258         } else {
03259             // write the chunk of data as specified
03260             progBuffer = (uint8_t *)data + i;
03261         }
03262 
03263         i2Cdev.writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
03264 
03265         // verify data if needed
03266         if (verify && verifyBuffer) {
03267             setMemoryBank(bank);
03268             setMemoryStartAddress(address);
03269             i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
03270             if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
03271                 /*Serial.print("Block write verification error, bank ");
03272                 Serial.print(bank, DEC);
03273                 Serial.print(", address ");
03274                 Serial.print(address, DEC);
03275                 Serial.print("!\nExpected:");
03276                 for (j = 0; j < chunkSize; j++) {
03277                     Serial.print(" 0x");
03278                     if (progBuffer[j] < 16) Serial.print("0");
03279                     Serial.print(progBuffer[j], HEX);
03280                 }
03281                 Serial.print("\nReceived:");
03282                 for (uint8_t j = 0; j < chunkSize; j++) {
03283                     Serial.print(" 0x");
03284                     if (verifyBuffer[i + j] < 16) Serial.print("0");
03285                     Serial.print(verifyBuffer[i + j], HEX);
03286                 }
03287                 Serial.print("\n");*/
03288                 free(verifyBuffer);
03289                 if (useProgMem) free(progBuffer);
03290                 return false; // uh oh.
03291             }
03292         }
03293 
03294         // increase byte index by [chunkSize]
03295         i += chunkSize;
03296 
03297         // uint8_t automatically wraps to 0 at 256
03298         address += chunkSize;
03299 
03300         // if we aren't done, update bank (if necessary) and address
03301         if (i < dataSize) {
03302             if (address == 0) bank++;
03303             setMemoryBank(bank);
03304             setMemoryStartAddress(address);
03305         }
03306     }
03307     if (verify) free(verifyBuffer);
03308     if (useProgMem) free(progBuffer);
03309     return true;
03310 }
03311 bool MPU6050::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify)
03312 {
03313     return writeMemoryBlock(data, dataSize, bank, address, verify, true);
03314 }
03315 bool MPU6050::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem)
03316 {
03317     uint8_t *progBuffer, success, special;
03318     uint16_t i, j;
03319     if (useProgMem) {
03320         progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
03321     }
03322 
03323     // config set data is a long string of blocks with the following structure:
03324     // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
03325     uint8_t bank, offset, length;
03326     for (i = 0; i < dataSize;) {
03327         if (useProgMem) {
03328             bank = pgm_read_byte(data + i++);
03329             offset = pgm_read_byte(data + i++);
03330             length = pgm_read_byte(data + i++);
03331         } else {
03332             bank = data[i++];
03333             offset = data[i++];
03334             length = data[i++];
03335         }
03336 
03337         // write data or perform special action
03338         if (length > 0) {
03339             // regular block of data to write
03340             /*Serial.print("Writing config block to bank ");
03341             Serial.print(bank);
03342             Serial.print(", offset ");
03343             Serial.print(offset);
03344             Serial.print(", length=");
03345             Serial.println(length);*/
03346             if (useProgMem) {
03347                 if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
03348                 for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
03349             } else {
03350                 progBuffer = (uint8_t *)data + i;
03351             }
03352             success = writeMemoryBlock(progBuffer, length, bank, offset, true);
03353             i += length;
03354         } else {
03355             // special instruction
03356             // NOTE: this kind of behavior (what and when to do certain things)
03357             // is totally undocumented. This code is in here based on observed
03358             // behavior only, and exactly why (or even whether) it has to be here
03359             // is anybody's guess for now.
03360             if (useProgMem) {
03361                 special = pgm_read_byte(data + i++);
03362             } else {
03363                 special = data[i++];
03364             }
03365             /*Serial.print("Special command code ");
03366             Serial.print(special, HEX);
03367             Serial.println(" found...");*/
03368             if (special == 0x01) {
03369                 // enable DMP-related interrupts
03370 
03371                 //setIntZeroMotionEnabled(true);
03372                 //setIntFIFOBufferOverflowEnabled(true);
03373                 //setIntDMPEnabled(true);
03374                 i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32);  // single operation
03375 
03376                 success = true;
03377             } else {
03378                 // unknown special command
03379                 success = false;
03380             }
03381         }
03382 
03383         if (!success) {
03384             if (useProgMem) free(progBuffer);
03385             return false; // uh oh
03386         }
03387     }
03388     if (useProgMem) free(progBuffer);
03389     return true;
03390 }
03391 bool MPU6050::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
03392 {
03393     return writeDMPConfigurationSet(data, dataSize, false);
03394 }
03395 
03396 // DMP_CFG_1 register
03397 
03398 uint8_t MPU6050::getDMPConfig1()
03399 {
03400     i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer);
03401     return buffer[0];
03402 }
03403 void MPU6050::setDMPConfig1(uint8_t config)
03404 {
03405     i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config);
03406 }
03407 
03408 // DMP_CFG_2 register
03409 
03410 uint8_t MPU6050::getDMPConfig2()
03411 {
03412     i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer);
03413     return buffer[0];
03414 }
03415 void MPU6050::setDMPConfig2(uint8_t config)
03416 {
03417     i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config);
03418 }