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