Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
MPU6050.cpp
00001 /* MPU6050 Library 00002 * 00003 * @author: Baser Kandehir 00004 * @date: July 16, 2015 00005 * @license: MIT license 00006 * 00007 * Copyright (c) 2015, Baser Kandehir, baser.kandehir@ieee.metu.edu.tr 00008 * 00009 * Permission is hereby granted, free of charge, to any person obtaining a copy 00010 * of this software and associated documentation files (the "Software"), to deal 00011 * in the Software without restriction, including without limitation the rights 00012 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 00013 * copies of the Software, and to permit persons to whom the Software is 00014 * furnished to do so, subject to the following conditions: 00015 * 00016 * The above copyright notice and this permission notice shall be included in 00017 * all copies or substantial portions of the Software. 00018 * 00019 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 00020 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 00021 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 00022 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 00023 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 00024 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 00025 * THE SOFTWARE. 00026 * 00027 */ 00028 00029 // Most of the code is adapted from Kris Winer's MPU6050 library 00030 00031 #include "MPU6050.h" 00032 00033 /* For LPC1768 board */ 00034 I2C i2c(p9,p10); // setup i2c (SDA,SCL) 00035 00036 /* For NUCLEO-F411RE board */ 00037 //static I2C i2c(D14,D15); // setup i2c (SDA,SCL) 00038 00039 /* Set initial input parameters */ 00040 00041 //! Acc Full Scale Range +-2G 4G 8G 16G 00042 enum Ascale 00043 { 00044 AFS_2G=0, 00045 AFS_4G, 00046 AFS_8G, 00047 AFS_16G 00048 }; 00049 00050 // Gyro Full Scale Range +-250 500 1000 2000 Degrees per second 00051 enum Gscale 00052 { 00053 GFS_250DPS=0, 00054 GFS_500DPS, 00055 GFS_1000DPS, 00056 GFS_2000DPS 00057 }; 00058 00059 // Sensor datas 00060 float ax,ay,az; 00061 float gx,gy,gz; 00062 int16_t accelData[3],gyroData[3],tempData; 00063 float accelBias[3] = {0, 0, 0}; // Bias corrections for acc 00064 float gyroBias[3] = {0, 0, 0}; // Bias corrections for gyro 00065 00066 // Specify sensor full scale range 00067 int Ascale = AFS_2G; 00068 int Gscale = GFS_250DPS; 00069 00070 // Scale resolutions per LSB for the sensors 00071 float aRes, gRes; 00072 00073 // Calculates Acc resolution 00074 //! :: Scope Resolution operator 00075 //! Define a function outside class definition 00076 //! Declaration must be done 00077 void MPU6050::getAres() 00078 { 00079 switch(Ascale) 00080 { 00081 case AFS_2G: 00082 aRes = 2.0/32768.0; 00083 break; 00084 case AFS_4G: 00085 aRes = 4.0/32768.0; 00086 break; 00087 case AFS_8G: 00088 aRes = 8.0/32768.0; 00089 break; 00090 case AFS_16G: 00091 aRes = 16.0/32768.0; 00092 break; 00093 } 00094 } 00095 00096 // Calculates Gyro resolution 00097 void MPU6050::getGres() 00098 { 00099 switch(Gscale) 00100 { 00101 case GFS_250DPS: 00102 gRes = 250.0/32768.0; 00103 break; 00104 case GFS_500DPS: 00105 gRes = 500.0/32768.0; 00106 break; 00107 case GFS_1000DPS: 00108 gRes = 1000.0/32768.0; 00109 break; 00110 case GFS_2000DPS: 00111 gRes = 2000.0/32768.0; 00112 break; 00113 } 00114 } 00115 00116 void MPU6050::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00117 { 00118 char data_write[2]; 00119 data_write[0]=subAddress; // I2C sends MSB first. Namely >>|subAddress|>>|data| 00120 data_write[1]=data; 00121 i2c.write(address,data_write,2,0); // i2c.write(int address, char* data, int length, bool repeated=false); 00122 } 00123 00124 char MPU6050::readByte(uint8_t address, uint8_t subAddress) 00125 { 00126 char data_read[1]; // will store the register data 00127 char data_write[1]; 00128 data_write[0]=subAddress; 00129 i2c.write(address,data_write,1,1); // have not stopped yet 00130 i2c.read(address,data_read,1,0); // read the data and stop 00131 return data_read[0]; 00132 } 00133 00134 void MPU6050::readBytes(uint8_t address, uint8_t subAddress, uint8_t byteNum, uint8_t* dest) 00135 { 00136 char data[14],data_write[1]; 00137 data_write[0]=subAddress; 00138 i2c.write(address,data_write,1,1); 00139 i2c.read(address,data,byteNum,0); 00140 for(int i=0;i<byteNum;i++) // equate the addresses 00141 dest[i]=data[i]; 00142 } 00143 00144 // Communication test: WHO_AM_I register reading 00145 void MPU6050::whoAmI() 00146 { 00147 uint8_t whoAmI = readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Should return 0x68 00148 pc.printf("I AM 0x%x \r\n",whoAmI); 00149 00150 if(whoAmI==0x68) 00151 { 00152 pc.printf("MPU6050 is online... \r\n"); 00153 led2=1; 00154 } 00155 else 00156 { 00157 pc.printf("Could not connect to MPU6050 \r\nCheck the connections... \r\n"); 00158 toggler1.attach(&toggle_led1,0.1); // toggles led1 every 100 ms 00159 } 00160 } 00161 00162 // Initializes MPU6050 with the following config: 00163 // PLL with X axis gyroscope reference 00164 // Sample rate: 200Hz for gyro and acc 00165 // Interrupts are disabled 00166 void MPU6050::init() 00167 { 00168 i2c.frequency(400000); // fast i2c: 400 kHz 00169 00170 /* Wake up the device */ 00171 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // wake up the device by clearing the sleep bit (bit6) 00172 wait_ms(100); // wait 100 ms to stabilize 00173 00174 /* Get stable time source */ 00175 // PLL with X axis gyroscope reference is used to improve stability 00176 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); 00177 00178 /* Configure Gyroscope and Accelerometer */ 00179 // Disable FSYNC, acc bandwidth: 44 Hz, gyro bandwidth: 42 Hz 00180 // Sample rates: 1kHz, maximum delay: 4.9ms (which is pretty good for a 200 Hz maximum rate) 00181 writeByte(MPU6050_ADDRESS, CONFIG, 0x03); 00182 00183 /* Set sample rate = gyroscope output rate/(1+SMPLRT_DIV) */ 00184 // SMPLRT_DIV=4 and sample rate=200 Hz (compatible with config above) 00185 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); 00186 00187 /* Accelerometer configuration */ 00188 uint8_t temp = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00189 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, temp & ~0xE0); // Clear self-test bits [7:5] 00190 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, temp & ~0x18); // Clear AFS bits [4:3] 00191 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, temp | Ascale<<3); // Set full scale range 00192 00193 /* Gyroscope configuration */ 00194 temp = readByte(MPU6050_ADDRESS, GYRO_CONFIG); 00195 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, temp & ~0xE0); // Clear self-test bits [7:5] 00196 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, temp & ~0x18); // Clear FS bits [4:3] 00197 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, temp | Gscale<<3); // Set full scale range 00198 } 00199 00200 // Resets the device 00201 void MPU6050::reset() 00202 { 00203 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // set bit7 to reset the device 00204 wait_ms(100); // wait 100 ms to stabilize 00205 } 00206 00207 void MPU6050::readAccelData(int16_t* dest) 00208 { 00209 uint8_t rawData[6]; // x,y,z acc data 00210 readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // read six raw data registers sequentially and write them into data array 00211 00212 /* Turn the MSB LSB into signed 16-bit value */ 00213 dest[0] = (int16_t)(((int16_t)rawData[0]<<8) | rawData[1]); // ACCEL_XOUT 00214 dest[1] = (int16_t)(((int16_t)rawData[2]<<8) | rawData[3]); // ACCEL_YOUT 00215 dest[2] = (int16_t)(((int16_t)rawData[4]<<8) | rawData[5]); // ACCEL_ZOUT 00216 } 00217 00218 void MPU6050::readGyroData(int16_t* dest) 00219 { 00220 uint8_t rawData[6]; // x,y,z gyro data 00221 readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // read the six raw data registers sequentially and write them into data array 00222 00223 /* Turn the MSB LSB into signed 16-bit value */ 00224 dest[0] = (int16_t)(((int16_t)rawData[0]<<8) | rawData[1]); // GYRO_XOUT 00225 dest[1] = (int16_t)(((int16_t)rawData[2]<<8) | rawData[3]); // GYRO_YOUT 00226 dest[2] = (int16_t)(((int16_t)rawData[4]<<8) | rawData[5]); // GYRO_ZOUT 00227 } 00228 00229 int16_t MPU6050::readTempData() 00230 { 00231 uint8_t rawData[2]; // temperature data 00232 readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // read the two raw data registers sequentially and write them into data array 00233 return (int16_t)(((int16_t)rawData[0]<<8) | rawData[1]); // turn the MSB LSB into signed 16-bit value 00234 } 00235 00236 /* Function which accumulates gyro and accelerometer data after device initialization. 00237 It calculates the average of the at-rest readings and 00238 then loads the resulting offsets into accelerometer and gyro bias registers. */ 00239 /* 00240 IMPORTANT NOTE: In this function; 00241 Resulting accel offsets are NOT pushed to the accel bias registers. accelBias[i] offsets are used in the main program. 00242 Resulting gyro offsets are pushed to the gyro bias registers. gyroBias[i] offsets are NOT used in the main program. 00243 Resulting data seems satisfactory. 00244 */ 00245 // dest1: accelBias dest2: gyroBias 00246 void MPU6050::calibrate(float* dest1, float* dest2) 00247 { 00248 uint8_t data[12]; // data array to hold acc and gyro x,y,z data 00249 uint16_t fifo_count, packet_count, count; 00250 int32_t accel_bias[3] = {0,0,0}; 00251 int32_t gyro_bias[3] = {0,0,0}; 00252 float aRes = 2.0/32768.0; 00253 float gRes = 250.0/32768.0; 00254 uint16_t accelsensitivity = 16384; // = 1/aRes = 16384 LSB/g 00255 //uint16_t gyrosensitivity = 131; // = 1/gRes = 131 LSB/dps 00256 00257 reset(); // Reset device 00258 00259 /* Get stable time source */ 00260 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // PLL with X axis gyroscope reference is used to improve stability 00261 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); // Disable accel only low power mode 00262 wait(0.2); 00263 00264 /* Configure device for bias calculation */ 00265 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00266 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00267 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00268 writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00269 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00270 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x04); // Reset FIFO 00271 wait(0.015); 00272 00273 /* Configure accel and gyro for bias calculation */ 00274 writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00275 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00276 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00277 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00278 00279 /* Configure FIFO to capture accelerometer and gyro data for bias calculation */ 00280 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00281 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable accelerometer and gyro for FIFO (max size 1024 bytes in MPU-6050) 00282 wait(0.08); // Sample rate is 1 kHz, accumulates 80 samples in 80 milliseconds. 00283 // accX: 2 byte, accY: 2 byte, accZ: 2 byte. gyroX: 2 byte, gyroY: 2 byte, gyroZ: 2 byte. 12*80=960 byte < 1024 byte 00284 00285 /* At end of sample accumulation, turn off FIFO sensor read */ 00286 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00287 readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // Read FIFO sample count 00288 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00289 packet_count = fifo_count/12; // The number of sets of full acc and gyro data for averaging. packet_count = 80 in this case 00290 00291 for(count=0; count<packet_count; count++) 00292 { 00293 int16_t accel_temp[3]={0,0,0}; 00294 int16_t gyro_temp[3]={0,0,0}; 00295 readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00296 00297 /* Form signed 16-bit integer for each sample in FIFO */ 00298 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; 00299 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00300 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00301 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00302 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00303 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00304 00305 /* Sum individual signed 16-bit biases to get accumulated signed 32-bit biases */ 00306 accel_bias[0] += (int32_t) accel_temp[0]; 00307 accel_bias[1] += (int32_t) accel_temp[1]; 00308 accel_bias[2] += (int32_t) accel_temp[2]; 00309 gyro_bias[0] += (int32_t) gyro_temp[0]; 00310 gyro_bias[1] += (int32_t) gyro_temp[1]; 00311 gyro_bias[2] += (int32_t) gyro_temp[2]; 00312 } 00313 00314 /* Normalize sums to get average count biases */ 00315 accel_bias[0] /= (int32_t) packet_count; 00316 accel_bias[1] /= (int32_t) packet_count; 00317 accel_bias[2] /= (int32_t) packet_count; 00318 gyro_bias[0] /= (int32_t) packet_count; 00319 gyro_bias[1] /= (int32_t) packet_count; 00320 gyro_bias[2] /= (int32_t) packet_count; 00321 00322 /* Remove gravity from the z-axis accelerometer bias calculation */ 00323 if(accel_bias[2] > 0) {accel_bias[2] -= (int32_t) accelsensitivity;} 00324 else {accel_bias[2] += (int32_t) accelsensitivity;} 00325 00326 /* Output scaled accelerometer biases for manual subtraction in the main program */ 00327 dest1[0] = accel_bias[0]*aRes; 00328 dest1[1] = accel_bias[1]*aRes; 00329 dest1[2] = accel_bias[2]*aRes; 00330 00331 /* Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup */ 00332 data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format 00333 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00334 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00335 data[3] = (-gyro_bias[1]/4) & 0xFF; 00336 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00337 data[5] = (-gyro_bias[2]/4) & 0xFF; 00338 00339 /* Push gyro biases to hardware registers */ 00340 writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 00341 writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); 00342 writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); 00343 writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); 00344 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); 00345 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); 00346 00347 /* Construct gyro bias in deg/s for later manual subtraction */ 00348 dest2[0] = gyro_bias[0]*gRes; 00349 dest2[1] = gyro_bias[1]*gRes; 00350 dest2[2] = gyro_bias[2]*gRes; 00351 } 00352 00353 void MPU6050::complementaryFilter(float* pitch, float* roll) 00354 { 00355 /* Get actual acc value */ 00356 readAccelData(accelData); 00357 getAres(); 00358 ax = accelData[0]*aRes - accelBias[0]; 00359 ay = accelData[1]*aRes - accelBias[1]; 00360 az = accelData[2]*aRes - accelBias[2]; 00361 00362 /* Get actual gyro value */ 00363 readGyroData(gyroData); 00364 getGres(); 00365 gx = gyroData[0]*gRes; // - gyroBias[0]; // Results are better without extracting gyroBias[i] 00366 gy = gyroData[1]*gRes; // - gyroBias[1]; 00367 gz = gyroData[2]*gRes; // - gyroBias[2]; 00368 00369 float pitchAcc, rollAcc; 00370 00371 /* Integrate the gyro data(deg/s) over time to get angle */ 00372 *pitch += gx * dt; // Angle around the X-axis 00373 *roll -= gy * dt; // Angle around the Y-axis 00374 00375 /* Turning around the X-axis results in a vector on the Y-axis 00376 whereas turning around the Y-axis results in a vector on the X-axis. */ 00377 pitchAcc = atan2f(accelData[1], accelData[2])*180/PI; 00378 rollAcc = atan2f(accelData[0], accelData[2])*180/PI; 00379 00380 /* Apply Complementary Filter */ 00381 *pitch = *pitch * 0.98 + pitchAcc * 0.02; 00382 *roll = *roll * 0.98 + rollAcc * 0.02; 00383 }
Generated on Sun Jul 17 2022 08:53:19 by
1.7.2