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.
Dependencies: L152RE_USBDevice STM32_USB48MHz Watchdog mbed
MPU6050.cpp
00001 //This file is an adaptation of Kris Winer's MPU6050 library and example code 00002 //See: https://developer.mbed.org/users/onehorse/code/MPU6050IMU/ 00003 //Specifically see https://developer.mbed.org/users/onehorse/code/MPU6050IMU/file/e0381ca0edac/main.cpp for license information :) 00004 00005 #include "MPU6050.h" 00006 #include "mbed.h" 00007 #include "math.h" 00008 00009 00010 00011 // Specify sensor full scale 00012 int Gscale = GFS_250DPS; 00013 int Ascale = AFS_8G; 00014 00015 //Set up I2C, (SDA,SCL) 00016 I2C MPU_i2c(PB_9, PB_8); 00017 00018 //DigitalOut myled(LED1); 00019 00020 float aRes, gRes; // scale resolutions per LSB for the sensors 00021 00022 // Pin definitions 00023 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 00024 00025 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00026 float ax, ay, az; // Stores the real accel value in g's 00027 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00028 float gx, gy, gz; // Stores the real gyro value in degrees per seconds 00029 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00030 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00031 float temperature; 00032 float SelfTest[6]; 00033 00034 //int delt_t = 0; // used to control display output rate 00035 //int count = 0; // used to control display output rate 00036 float sum = 0; 00037 uint32_t sumCount = 0; 00038 00039 // parameters for 6 DoF sensor fusion calculations 00040 float PI = 3.14159265358979323846f; 00041 float GyroMeasError = PI * (60.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3 00042 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00043 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00044 float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value 00045 float pitch, yaw, roll; 00046 float deltat = 0.0f; // integration interval for both filter schemes 00047 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00048 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00049 00050 00051 void MPU6050::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00052 { 00053 char data_write[2]; 00054 data_write[0] = subAddress; 00055 data_write[1] = data; 00056 __disable_irq(); 00057 MPU_i2c.write(address, data_write, 2, 0); 00058 __enable_irq(); 00059 } 00060 00061 char MPU6050::readByte(uint8_t address, uint8_t subAddress) 00062 { 00063 char data[1]; // `data` will store the register data 00064 char data_write[1]; 00065 data_write[0] = subAddress; 00066 __disable_irq(); 00067 MPU_i2c.write(address, data_write, 1, 1); // no stop 00068 MPU_i2c.read(address, data, 1, 0); 00069 __enable_irq(); 00070 return data[0]; 00071 } 00072 00073 void MPU6050::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00074 { 00075 char data[14]; 00076 char data_write[1]; 00077 data_write[0] = subAddress; 00078 __disable_irq(); 00079 MPU_i2c.write(address, data_write, 1, 1); // no stop 00080 MPU_i2c.read(address, data, count, 0); 00081 __enable_irq(); 00082 for(int ii = 0; ii < count; ii++) { 00083 dest[ii] = data[ii]; 00084 } 00085 } 00086 00087 00088 void MPU6050::getGres() { 00089 switch (Gscale) 00090 { 00091 // Possible gyro scales (and their register bit settings) are: 00092 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00093 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00094 case GFS_250DPS: 00095 gRes = 250.0/32768.0; 00096 break; 00097 case GFS_500DPS: 00098 gRes = 500.0/32768.0; 00099 break; 00100 case GFS_1000DPS: 00101 gRes = 1000.0/32768.0; 00102 break; 00103 case GFS_2000DPS: 00104 gRes = 2000.0/32768.0; 00105 break; 00106 } 00107 } 00108 00109 void MPU6050::getAres() { 00110 switch (Ascale) 00111 { 00112 // Possible accelerometer scales (and their register bit settings) are: 00113 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00114 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00115 case AFS_2G: 00116 aRes = 2.0/32768.0; 00117 break; 00118 case AFS_4G: 00119 aRes = 4.0/32768.0; 00120 break; 00121 case AFS_8G: 00122 aRes = 8.0/32768.0; 00123 break; 00124 case AFS_16G: 00125 aRes = 16.0/32768.0; 00126 break; 00127 } 00128 } 00129 00130 00131 void MPU6050::readAccelData(int16_t * destination) 00132 { 00133 uint8_t rawData[6]; // x/y/z accel register data stored here 00134 readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00135 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00136 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00137 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00138 } 00139 00140 void MPU6050::readGyroData(int16_t * destination) 00141 { 00142 uint8_t rawData[6]; // x/y/z gyro register data stored here 00143 readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00144 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00145 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00146 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00147 } 00148 00149 int16_t MPU6050::readTempData() 00150 { 00151 uint8_t rawData[2]; // x/y/z gyro register data stored here 00152 readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00153 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00154 } 00155 00156 00157 00158 // Configure the motion detection control for low power accelerometer mode 00159 void MPU6050::LowPowerAccelOnly() 00160 { 00161 00162 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly 00163 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration 00164 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 00165 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out 00166 // consideration for these threshold evaluations; otherwise, the flags would be set all the time! 00167 00168 uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00169 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6] 00170 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running 00171 00172 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00173 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5] 00174 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running 00175 00176 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00177 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00178 // Set high-pass filter to 0) reset (disable), 1) 5 Hz, 2) 2.5 Hz, 3) 1.25 Hz, 4) 0.63 Hz, or 7) Hold 00179 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter 00180 00181 c = readByte(MPU6050_ADDRESS, CONFIG); 00182 writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0] 00183 writeByte(MPU6050_ADDRESS, CONFIG, c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate 00184 00185 c = readByte(MPU6050_ADDRESS, INT_ENABLE); 00186 writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts 00187 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40); // Enable motion threshold (bits 5) interrupt only 00188 00189 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold 00190 // for at least the counter duration 00191 writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg 00192 writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate 00193 00194 wait(0.1); // Add delay for accumulation of samples 00195 00196 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00197 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00198 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7; hold the initial accleration value as a referance 00199 00200 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00201 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7] 00202 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2]) 00203 00204 c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00205 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5 00206 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts 00207 00208 } 00209 00210 00211 void MPU6050::resetMPU6050() { 00212 // reset device 00213 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00214 wait(0.1); 00215 } 00216 00217 00218 void MPU6050::initMPU6050() 00219 { 00220 // Initialize MPU6050 device 00221 // wake up device 00222 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00223 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00224 00225 // get stable time source 00226 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00227 00228 // Configure Gyro and Accelerometer 00229 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00230 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00231 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00232 writeByte(MPU6050_ADDRESS, CONFIG, 0x03); 00233 00234 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00235 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00236 00237 // Set gyroscope full scale range 00238 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00239 uint8_t c = readByte(MPU6050_ADDRESS, GYRO_CONFIG); 00240 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00241 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00242 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00243 00244 // Set accelerometer configuration 00245 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00246 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00247 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00248 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00249 00250 // Configure Interrupts and Bypass Enable 00251 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00252 // can join the I2C bus and all can be controlled by the Arduino as master 00253 writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22); 00254 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00255 } 00256 00257 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00258 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00259 void MPU6050::calibrateMPU6050(float * dest1, float * dest2) 00260 { 00261 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00262 uint16_t ii, packet_count, fifo_count; 00263 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00264 00265 // reset device, reset all registers, clear gyro and accelerometer bias registers 00266 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00267 wait(0.1); 00268 00269 // get stable time source 00270 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00271 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); 00272 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 00273 wait(0.2); 00274 00275 // Configure device for bias calculation 00276 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00277 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00278 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00279 writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00280 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00281 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00282 wait(0.015); 00283 00284 // Configure MPU6050 gyro and accelerometer for bias calculation 00285 writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00286 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00287 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00288 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00289 00290 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00291 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00292 00293 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00294 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00295 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050) 00296 wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes 00297 00298 // At end of sample accumulation, turn off FIFO sensor read 00299 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00300 readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00301 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00302 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00303 00304 for (ii = 0; ii < packet_count; ii++) { 00305 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00306 readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00307 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00308 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00309 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00310 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00311 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00312 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00313 00314 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00315 accel_bias[1] += (int32_t) accel_temp[1]; 00316 accel_bias[2] += (int32_t) accel_temp[2]; 00317 gyro_bias[0] += (int32_t) gyro_temp[0]; 00318 gyro_bias[1] += (int32_t) gyro_temp[1]; 00319 gyro_bias[2] += (int32_t) gyro_temp[2]; 00320 00321 } 00322 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00323 accel_bias[1] /= (int32_t) packet_count; 00324 accel_bias[2] /= (int32_t) packet_count; 00325 gyro_bias[0] /= (int32_t) packet_count; 00326 gyro_bias[1] /= (int32_t) packet_count; 00327 gyro_bias[2] /= (int32_t) packet_count; 00328 00329 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00330 else {accel_bias[2] += (int32_t) accelsensitivity;} 00331 00332 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00333 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 00334 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00335 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00336 data[3] = (-gyro_bias[1]/4) & 0xFF; 00337 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00338 data[5] = (-gyro_bias[2]/4) & 0xFF; 00339 00340 // Push gyro biases to hardware registers 00341 writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 00342 writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); 00343 writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); 00344 writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); 00345 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); 00346 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); 00347 00348 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00349 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00350 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00351 00352 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00353 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00354 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00355 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00356 // the accelerometer biases calculated above must be divided by 8. 00357 00358 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00359 readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00360 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00361 readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00362 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00363 readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00364 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00365 00366 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00367 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00368 00369 for(ii = 0; ii < 3; ii++) { 00370 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00371 } 00372 00373 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00374 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00375 accel_bias_reg[1] -= (accel_bias[1]/8); 00376 accel_bias_reg[2] -= (accel_bias[2]/8); 00377 00378 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00379 data[1] = (accel_bias_reg[0]) & 0xFF; 00380 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00381 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00382 data[3] = (accel_bias_reg[1]) & 0xFF; 00383 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00384 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00385 data[5] = (accel_bias_reg[2]) & 0xFF; 00386 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00387 00388 // Push accelerometer biases to hardware registers 00389 // writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]); 00390 // writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]); 00391 // writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]); 00392 // writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]); 00393 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]); 00394 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]); 00395 00396 // Output scaled accelerometer biases for manual subtraction in the main program 00397 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00398 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00399 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00400 } 00401 00402 00403 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00404 void MPU6050::MPU6050SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00405 { 00406 uint8_t rawData[4] = {0, 0, 0, 0}; 00407 uint8_t selfTest[6]; 00408 float factoryTrim[6]; 00409 00410 // Configure the accelerometer for self-test 00411 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g 00412 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00413 wait(0.25); // Delay a while to let the device execute the self-test 00414 rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results 00415 rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results 00416 rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results 00417 rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results 00418 // Extract the acceleration test results first 00419 selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer 00420 selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer 00421 selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer 00422 // Extract the gyration test results first 00423 selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer 00424 selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer 00425 selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer 00426 // Process results to allow final comparison with factory set values 00427 factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation 00428 factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation 00429 factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation 00430 factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation 00431 factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation 00432 factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation 00433 00434 // Output self-test results and factory trim calculation if desired 00435 // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); 00436 // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); 00437 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); 00438 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); 00439 00440 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00441 // To get to percent, must multiply by 100 and subtract result from 100 00442 for (int i = 0; i < 6; i++) { 00443 destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences 00444 } 00445 00446 } 00447 00448 00449 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00450 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00451 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative 00452 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00453 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00454 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00455 void MPU6050::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz) 00456 { 00457 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00458 float norm; // vector norm 00459 float f1, f2, f3; // objective funcyion elements 00460 float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements 00461 float qDot1, qDot2, qDot3, qDot4; 00462 float hatDot1, hatDot2, hatDot3, hatDot4; 00463 float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error 00464 00465 // Auxiliary variables to avoid repeated arithmetic 00466 float _halfq1 = 0.5f * q1; 00467 float _halfq2 = 0.5f * q2; 00468 float _halfq3 = 0.5f * q3; 00469 float _halfq4 = 0.5f * q4; 00470 float _2q1 = 2.0f * q1; 00471 float _2q2 = 2.0f * q2; 00472 float _2q3 = 2.0f * q3; 00473 float _2q4 = 2.0f * q4; 00474 // float _2q1q3 = 2.0f * q1 * q3; 00475 // float _2q3q4 = 2.0f * q3 * q4; 00476 00477 // Normalise accelerometer measurement 00478 norm = sqrt(ax * ax + ay * ay + az * az); 00479 if (norm == 0.0f) return; // handle NaN (INF ?) 00480 norm = 1.0f/norm; 00481 ax *= norm; 00482 ay *= norm; 00483 az *= norm; 00484 00485 // Compute the objective function and Jacobian 00486 f1 = _2q2 * q4 - _2q1 * q3 - ax; 00487 f2 = _2q1 * q2 + _2q3 * q4 - ay; 00488 f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az; 00489 J_11or24 = _2q3; 00490 J_12or23 = _2q4; 00491 J_13or22 = _2q1; 00492 J_14or21 = _2q2; 00493 J_32 = 2.0f * J_14or21; 00494 J_33 = 2.0f * J_11or24; 00495 00496 // Compute the gradient (matrix multiplication) 00497 hatDot1 = J_14or21 * f2 - J_11or24 * f1; 00498 hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3; 00499 hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1; 00500 hatDot4 = J_14or21 * f1 + J_11or24 * f2; 00501 00502 // Normalize the gradient 00503 norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4); 00504 if (norm == 0.0f) return; // handle NaN (INF ?) 00505 hatDot1 /= norm; 00506 hatDot2 /= norm; 00507 hatDot3 /= norm; 00508 hatDot4 /= norm; 00509 00510 // Compute estimated gyroscope biases 00511 gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3; 00512 gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2; 00513 gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1; 00514 00515 // Compute and remove gyroscope biases 00516 gbiasx += gerrx * deltat * zeta; 00517 gbiasy += gerry * deltat * zeta; 00518 gbiasz += gerrz * deltat * zeta; 00519 // gx -= gbiasx; 00520 // gy -= gbiasy; 00521 // gz -= gbiasz; 00522 00523 // Compute the quaternion derivative 00524 qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz; 00525 qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy; 00526 qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx; 00527 qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx; 00528 00529 // Compute then integrate estimated quaternion derivative 00530 q1 += (qDot1 -(beta * hatDot1)) * deltat; 00531 q2 += (qDot2 -(beta * hatDot2)) * deltat; 00532 q3 += (qDot3 -(beta * hatDot3)) * deltat; 00533 q4 += (qDot4 -(beta * hatDot4)) * deltat; 00534 00535 // Normalize the quaternion 00536 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00537 if (norm == 0.0f) return; // handle NaN (INF ?) 00538 norm = 1.0f/norm; 00539 q[0] = q1 * norm; 00540 q[1] = q2 * norm; 00541 q[2] = q3 * norm; 00542 q[3] = q4 * norm; 00543 00544 } 00545 00546 bool MPU6050::motion_sensor_init() 00547 { 00548 00549 00550 // Read the WHO_AM_I register, this is a good test of communication 00551 uint8_t whoami = readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Read WHO_AM_I register for MPU-6050 00552 //serial.printf("I AM 0x%x\n\r", whoami); 00553 //serial.printf("I SHOULD BE 0x68\n\r"); 00554 00555 if (whoami == 0x68) { // WHO_AM_I should always be 0x68 00556 // serial.printf("MPU6050 is online..."); 00557 wait(1); 00558 00559 00560 MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values 00561 /* 00562 serial.printf("x-axis self test: acceleration trim within : "); 00563 serial.printf("%f", SelfTest[0]); 00564 serial.printf("% of factory value \n\r"); 00565 serial.printf("y-axis self test: acceleration trim within : "); 00566 serial.printf("%f", SelfTest[1]); 00567 serial.printf("% of factory value \n\r"); 00568 serial.printf("z-axis self test: acceleration trim within : "); 00569 serial.printf("%f", SelfTest[2]); 00570 serial.printf("% of factory value \n\r"); 00571 serial.printf("x-axis self test: gyration trim within : "); 00572 serial.printf("%f", SelfTest[3]); 00573 serial.printf("% of factory value \n\r"); 00574 serial.printf("y-axis self test: gyration trim within : "); 00575 serial.printf("%f", SelfTest[4]); 00576 serial.printf("% of factory value \n\r"); 00577 serial.printf("z-axis self test: gyration trim within : "); 00578 serial.printf("%f", SelfTest[5]); 00579 serial.printf("% of factory value \n\r"); 00580 */ 00581 wait(1); 00582 00583 if(SelfTest[0] < 1.0f && SelfTest[1] < 1.0f && SelfTest[2] < 1.0f && SelfTest[3] < 1.0f && SelfTest[4] < 1.0f && SelfTest[5] < 1.0f) { 00584 resetMPU6050(); // Reset registers to default in preparation for device calibration 00585 initMPU6050(); 00586 //serial.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00587 00588 return TRUE; 00589 } else { 00590 //serial.printf("Device did not the pass self-test!\n\r"); 00591 return FALSE; 00592 00593 } 00594 } else { 00595 //serial.printf("Could not connect to MPU6050: \n\r"); 00596 //serial.printf("%#x \n", whoami); 00597 00598 return FALSE; 00599 } 00600 00601 00602 } 00603 00604 bool MPU6050::motion_update_data(MPU_data_type *new_data, int current_time_us) 00605 { 00606 if(readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { 00607 readAccelData(accelCount); // Read the x/y/z adc values 00608 getAres(); 00609 00610 // Now we'll calculate the accleration value into actual g's 00611 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set 00612 ay = (float)accelCount[1]*aRes - accelBias[1]; 00613 az = (float)accelCount[2]*aRes - accelBias[2]; 00614 00615 readGyroData(gyroCount); // Read the x/y/z adc values 00616 getGres(); 00617 00618 // Calculate the gyro value into actual degrees per second 00619 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set 00620 gy = (float)gyroCount[1]*gRes; // - gyroBias[1]; 00621 gz = (float)gyroCount[2]*gRes; // - gyroBias[2]; 00622 00623 tempCount = readTempData(); // Read the x/y/z adc values 00624 temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade 00625 00626 00627 Now = current_time_us; 00628 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00629 lastUpdate = Now; 00630 00631 sum += deltat; 00632 sumCount++; 00633 00634 if(lastUpdate - firstUpdate > 10000000.0f) { 00635 beta = 0.04; // decrease filter gain after stabilized 00636 zeta = 0.015; // increase bias drift gain after stabilized 00637 } 00638 00639 // Pass gyro rate as rad/s 00640 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f); 00641 00642 00643 00644 00645 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 00646 // In this coordinate system, the positive z-axis is down toward Earth. 00647 // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 00648 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 00649 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 00650 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 00651 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 00652 // applied in the correct order which for this configuration is yaw, pitch, and then roll. 00653 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 00654 yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); 00655 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00656 roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); 00657 pitch *= 180.0f / PI; 00658 yaw *= 180.0f / PI; 00659 roll *= 180.0f / PI; 00660 /* 00661 new_data->ax = (int) (ax / 16384.0f); 00662 new_data->ay = (int) (ay / 16384.0f); 00663 new_data->az = (int) (az / 16384.0f); 00664 new_data->yaw = (int) (yaw / 16384.0f); 00665 new_data->pitch = (int) (pitch / 16384.0f); 00666 new_data->roll = (int) (roll / 16384.0f); 00667 */ 00668 new_data->ax = (int) (ax * 1000); 00669 new_data->ay = (int) (ay * 1000); 00670 new_data->az = (int) (az * 1000); 00671 new_data->yaw = (int) (yaw * 10); 00672 new_data->pitch = (int) (pitch * 10); 00673 new_data->roll = (int) (roll * 10); 00674 return TRUE; 00675 00676 } else { 00677 return FALSE; 00678 } 00679 00680 } 00681 00682 void MPU6050_set_I2C_freq(int i2c_frequency) 00683 { 00684 MPU_i2c.frequency(i2c_frequency); 00685 } 00686 00687 00688 00689
Generated on Sat Jul 16 2022 18:01:36 by
 1.7.2
 1.7.2