Aloïs Wolff / MPU6050_tmp

Dependents:   MbedFreeIMU gurvanAHRS

Fork of MPU6050 by Simon Garfieldsg

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