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