Osman Kamerić / MPU6050

Dependents:   kopija_NUCLEO_CELL_LOCKER_copy

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