Ported from Arduino Library : https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050

Dependents:   IMU cube-puck button-puck test_program_3

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