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: IMU MODSERIAL Servo mbed
Fork of RTOS_Controller by
MPU6050.h
00001 #ifndef MPU6050_H 00002 #define MPU6050_H 00003 00004 #include "mbed.h" 00005 #include "math.h" 00006 00007 // Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device 00008 // Invensense Inc., www.invensense.com 00009 // See also MPU-6050 Register Map and Descriptions, Revision 4.0, RM-MPU-6050A-00, 9/12/2012 for registers not listed in 00010 // above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor 00011 // 00012 #define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD 00013 #define YGOFFS_TC 0x01 00014 #define ZGOFFS_TC 0x02 00015 #define X_FINE_GAIN 0x03 // [7:0] fine gain 00016 #define Y_FINE_GAIN 0x04 00017 #define Z_FINE_GAIN 0x05 00018 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 00019 #define XA_OFFSET_L_TC 0x07 00020 #define YA_OFFSET_H 0x08 00021 #define YA_OFFSET_L_TC 0x09 00022 #define ZA_OFFSET_H 0x0A 00023 #define ZA_OFFSET_L_TC 0x0B 00024 #define SELF_TEST_X 0x0D 00025 #define SELF_TEST_Y 0x0E 00026 #define SELF_TEST_Z 0x0F 00027 #define SELF_TEST_A 0x10 00028 #define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope; supported in MPU-6050? 00029 #define XG_OFFS_USRL 0x14 00030 #define YG_OFFS_USRH 0x15 00031 #define YG_OFFS_USRL 0x16 00032 #define ZG_OFFS_USRH 0x17 00033 #define ZG_OFFS_USRL 0x18 00034 #define SMPLRT_DIV 0x19 00035 #define CONFIG 0x1A 00036 #define GYRO_CONFIG 0x1B 00037 #define ACCEL_CONFIG 0x1C 00038 #define FF_THR 0x1D // Free-fall 00039 #define FF_DUR 0x1E // Free-fall 00040 #define MOT_THR 0x1F // Motion detection threshold bits [7:0] 00041 #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms 00042 #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] 00043 #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms 00044 #define FIFO_EN 0x23 00045 #define I2C_MST_CTRL 0x24 00046 #define I2C_SLV0_ADDR 0x25 00047 #define I2C_SLV0_REG 0x26 00048 #define I2C_SLV0_CTRL 0x27 00049 #define I2C_SLV1_ADDR 0x28 00050 #define I2C_SLV1_REG 0x29 00051 #define I2C_SLV1_CTRL 0x2A 00052 #define I2C_SLV2_ADDR 0x2B 00053 #define I2C_SLV2_REG 0x2C 00054 #define I2C_SLV2_CTRL 0x2D 00055 #define I2C_SLV3_ADDR 0x2E 00056 #define I2C_SLV3_REG 0x2F 00057 #define I2C_SLV3_CTRL 0x30 00058 #define I2C_SLV4_ADDR 0x31 00059 #define I2C_SLV4_REG 0x32 00060 #define I2C_SLV4_DO 0x33 00061 #define I2C_SLV4_CTRL 0x34 00062 #define I2C_SLV4_DI 0x35 00063 #define I2C_MST_STATUS 0x36 00064 #define INT_PIN_CFG 0x37 00065 #define INT_ENABLE 0x38 00066 #define DMP_INT_STATUS 0x39 // Check DMP interrupt 00067 #define INT_STATUS 0x3A 00068 #define ACCEL_XOUT_H 0x3B 00069 #define ACCEL_XOUT_L 0x3C 00070 #define ACCEL_YOUT_H 0x3D 00071 #define ACCEL_YOUT_L 0x3E 00072 #define ACCEL_ZOUT_H 0x3F 00073 #define ACCEL_ZOUT_L 0x40 00074 #define TEMP_OUT_H 0x41 00075 #define TEMP_OUT_L 0x42 00076 #define GYRO_XOUT_H 0x43 00077 #define GYRO_XOUT_L 0x44 00078 #define GYRO_YOUT_H 0x45 00079 #define GYRO_YOUT_L 0x46 00080 #define GYRO_ZOUT_H 0x47 00081 #define GYRO_ZOUT_L 0x48 00082 #define EXT_SENS_DATA_00 0x49 00083 #define EXT_SENS_DATA_01 0x4A 00084 #define EXT_SENS_DATA_02 0x4B 00085 #define EXT_SENS_DATA_03 0x4C 00086 #define EXT_SENS_DATA_04 0x4D 00087 #define EXT_SENS_DATA_05 0x4E 00088 #define EXT_SENS_DATA_06 0x4F 00089 #define EXT_SENS_DATA_07 0x50 00090 #define EXT_SENS_DATA_08 0x51 00091 #define EXT_SENS_DATA_09 0x52 00092 #define EXT_SENS_DATA_10 0x53 00093 #define EXT_SENS_DATA_11 0x54 00094 #define EXT_SENS_DATA_12 0x55 00095 #define EXT_SENS_DATA_13 0x56 00096 #define EXT_SENS_DATA_14 0x57 00097 #define EXT_SENS_DATA_15 0x58 00098 #define EXT_SENS_DATA_16 0x59 00099 #define EXT_SENS_DATA_17 0x5A 00100 #define EXT_SENS_DATA_18 0x5B 00101 #define EXT_SENS_DATA_19 0x5C 00102 #define EXT_SENS_DATA_20 0x5D 00103 #define EXT_SENS_DATA_21 0x5E 00104 #define EXT_SENS_DATA_22 0x5F 00105 #define EXT_SENS_DATA_23 0x60 00106 #define MOT_DETECT_STATUS 0x61 00107 #define I2C_SLV0_DO 0x63 00108 #define I2C_SLV1_DO 0x64 00109 #define I2C_SLV2_DO 0x65 00110 #define I2C_SLV3_DO 0x66 00111 #define I2C_MST_DELAY_CTRL 0x67 00112 #define SIGNAL_PATH_RESET 0x68 00113 #define MOT_DETECT_CTRL 0x69 00114 #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP 00115 #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode 00116 #define PWR_MGMT_2 0x6C 00117 #define DMP_BANK 0x6D // Activates a specific bank in the DMP 00118 #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank 00119 #define DMP_REG 0x6F // Register in DMP from which to read or to which to write 00120 #define DMP_REG_1 0x70 00121 #define DMP_REG_2 0x71 00122 #define FIFO_COUNTH 0x72 00123 #define FIFO_COUNTL 0x73 00124 #define FIFO_R_W 0x74 00125 #define WHO_AM_I_MPU6050 0x75 // Should return 0x68 00126 00127 // Using the GY-521 breakout board, I set ADO to 0 by grounding through a 4k7 resistor 00128 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 00129 #define ADO 0 00130 #if ADO 00131 #define MPU6050_ADDRESS 0x69<<1 // Device address when ADO = 1 00132 #else 00133 #define MPU6050_ADDRESS 0x68<<1 // Device address when ADO = 0 00134 #endif 00135 00136 // Set initial input parameters 00137 enum Ascale { 00138 AFS_2G = 0, 00139 AFS_4G, 00140 AFS_8G, 00141 AFS_16G 00142 }; 00143 00144 enum Gscale { 00145 GFS_250DPS = 0, 00146 GFS_500DPS, 00147 GFS_1000DPS, 00148 GFS_2000DPS 00149 }; 00150 00151 // Specify sensor full scale 00152 int Gscale = GFS_250DPS; 00153 int Ascale = AFS_2G; 00154 00155 //Set up I2C, (SDA,SCL) 00156 I2C i2c(I2C_SDA, I2C_SCL); 00157 00158 float aRes, gRes; // scale resolutions per LSB for the sensors 00159 00160 // Pin definitions 00161 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 00162 00163 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00164 float ax, ay, az; // Stores the real accel value in g's 00165 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00166 float gx, gy, gz; // Stores the real gyro value in degrees per seconds 00167 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00168 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00169 float temperature; 00170 float SelfTest[6]; 00171 00172 int delt_t = 0; // used to control display output rate 00173 int count = 0; // used to control display output rate 00174 00175 // parameters for 6 DoF sensor fusion calculations 00176 float PI = 3.14159265358979323846f; 00177 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 00178 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00179 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00180 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 00181 float pitch, yaw, roll; 00182 float deltat = 0.0f; // integration interval for both filter schemes 00183 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00184 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00185 00186 class MPU6050 00187 { 00188 00189 protected: 00190 00191 public: 00192 //=================================================================================================================== 00193 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00194 //=================================================================================================================== 00195 00196 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) { 00197 char data_write[2]; 00198 data_write[0] = subAddress; 00199 data_write[1] = data; 00200 i2c.write(address, data_write, 2, 0); 00201 } 00202 00203 char readByte(uint8_t address, uint8_t subAddress) { 00204 char data[1]; // `data` will store the register data 00205 char data_write[1]; 00206 data_write[0] = subAddress; 00207 i2c.write(address, data_write, 1, 1); // no stop 00208 i2c.read(address, data, 1, 0); 00209 return data[0]; 00210 } 00211 00212 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { 00213 char data[14]; 00214 char data_write[1]; 00215 data_write[0] = subAddress; 00216 i2c.write(address, data_write, 1, 1); // no stop 00217 i2c.read(address, data, count, 0); 00218 for(int ii = 0; ii < count; ii++) { 00219 dest[ii] = data[ii]; 00220 } 00221 } 00222 00223 00224 void getGres() { 00225 switch (Gscale) { 00226 // Possible gyro scales (and their register bit settings) are: 00227 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00228 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00229 case GFS_250DPS: 00230 gRes = 250.0/32768.0; 00231 break; 00232 case GFS_500DPS: 00233 gRes = 500.0/32768.0; 00234 break; 00235 case GFS_1000DPS: 00236 gRes = 1000.0/32768.0; 00237 break; 00238 case GFS_2000DPS: 00239 gRes = 2000.0/32768.0; 00240 break; 00241 } 00242 } 00243 00244 void getAres() { 00245 switch (Ascale) { 00246 // Possible accelerometer scales (and their register bit settings) are: 00247 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00248 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00249 case AFS_2G: 00250 aRes = 2.0/32768.0; 00251 break; 00252 case AFS_4G: 00253 aRes = 4.0/32768.0; 00254 break; 00255 case AFS_8G: 00256 aRes = 8.0/32768.0; 00257 break; 00258 case AFS_16G: 00259 aRes = 16.0/32768.0; 00260 break; 00261 } 00262 } 00263 00264 00265 void readAccelData(int16_t * destination) { 00266 uint8_t rawData[6]; // x/y/z accel register data stored here 00267 readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00268 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00269 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00270 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00271 } 00272 00273 void readGyroData(int16_t * destination) { 00274 uint8_t rawData[6]; // x/y/z gyro register data stored here 00275 readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00276 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00277 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00278 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00279 } 00280 00281 int16_t readTempData() { 00282 uint8_t rawData[2]; // x/y/z gyro register data stored here 00283 readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00284 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00285 } 00286 00287 00288 00289 // Configure the motion detection control for low power accelerometer mode 00290 void LowPowerAccelOnly() { 00291 00292 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly 00293 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration 00294 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 00295 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out 00296 // consideration for these threshold evaluations; otherwise, the flags would be set all the time! 00297 00298 uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00299 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6] 00300 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running 00301 00302 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00303 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5] 00304 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running 00305 00306 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00307 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00308 // 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 00309 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter 00310 00311 c = readByte(MPU6050_ADDRESS, CONFIG); 00312 writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0] 00313 writeByte(MPU6050_ADDRESS, CONFIG, c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate 00314 00315 c = readByte(MPU6050_ADDRESS, INT_ENABLE); 00316 writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts 00317 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40); // Enable motion threshold (bits 5) interrupt only 00318 00319 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold 00320 // for at least the counter duration 00321 writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg 00322 writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate 00323 00324 wait(0.1); // Add delay for accumulation of samples 00325 00326 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00327 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00328 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7; hold the initial accleration value as a referance 00329 00330 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00331 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7] 00332 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2]) 00333 00334 c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00335 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5 00336 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts 00337 00338 } 00339 00340 00341 void resetMPU6050() { 00342 // reset device 00343 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00344 wait(0.1); 00345 } 00346 00347 00348 void initMPU6050() { 00349 // Initialize MPU6050 device 00350 // wake up device 00351 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00352 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00353 00354 // get stable time source 00355 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00356 00357 // Configure Gyro and Accelerometer 00358 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00359 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00360 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00361 writeByte(MPU6050_ADDRESS, CONFIG, 0x03); 00362 00363 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00364 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00365 00366 // Set gyroscope full scale range 00367 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00368 uint8_t c = readByte(MPU6050_ADDRESS, GYRO_CONFIG); 00369 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00370 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00371 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00372 00373 // Set accelerometer configuration 00374 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00375 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00376 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00377 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00378 00379 // Configure Interrupts and Bypass Enable 00380 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00381 // can join the I2C bus and all can be controlled by the Arduino as master 00382 writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22); 00383 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00384 } 00385 00386 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00387 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00388 void calibrateMPU6050(float * dest1, float * dest2) { 00389 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00390 uint16_t ii, packet_count, fifo_count; 00391 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00392 00393 // reset device, reset all registers, clear gyro and accelerometer bias registers 00394 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00395 wait(0.1); 00396 00397 // get stable time source 00398 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00399 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); 00400 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 00401 wait(0.2); 00402 00403 // Configure device for bias calculation 00404 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00405 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00406 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00407 writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00408 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00409 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00410 wait(0.015); 00411 00412 // Configure MPU6050 gyro and accelerometer for bias calculation 00413 writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00414 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00415 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00416 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00417 00418 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00419 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00420 00421 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00422 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00423 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050) 00424 wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes 00425 00426 // At end of sample accumulation, turn off FIFO sensor read 00427 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00428 readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00429 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00430 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00431 00432 for (ii = 0; ii < packet_count; ii++) { 00433 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00434 readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00435 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00436 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00437 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00438 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00439 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00440 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00441 00442 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00443 accel_bias[1] += (int32_t) accel_temp[1]; 00444 accel_bias[2] += (int32_t) accel_temp[2]; 00445 gyro_bias[0] += (int32_t) gyro_temp[0]; 00446 gyro_bias[1] += (int32_t) gyro_temp[1]; 00447 gyro_bias[2] += (int32_t) gyro_temp[2]; 00448 00449 } 00450 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00451 accel_bias[1] /= (int32_t) packet_count; 00452 accel_bias[2] /= (int32_t) packet_count; 00453 gyro_bias[0] /= (int32_t) packet_count; 00454 gyro_bias[1] /= (int32_t) packet_count; 00455 gyro_bias[2] /= (int32_t) packet_count; 00456 00457 if(accel_bias[2] > 0L) { 00458 accel_bias[2] -= (int32_t) accelsensitivity; // Remove gravity from the z-axis accelerometer bias calculation 00459 } else { 00460 accel_bias[2] += (int32_t) accelsensitivity; 00461 } 00462 00463 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00464 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 00465 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00466 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00467 data[3] = (-gyro_bias[1]/4) & 0xFF; 00468 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00469 data[5] = (-gyro_bias[2]/4) & 0xFF; 00470 00471 // Push gyro biases to hardware registers 00472 writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 00473 writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); 00474 writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); 00475 writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); 00476 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); 00477 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); 00478 00479 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00480 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00481 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00482 00483 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00484 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00485 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00486 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00487 // the accelerometer biases calculated above must be divided by 8. 00488 00489 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00490 readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00491 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00492 readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00493 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00494 readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00495 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00496 00497 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00498 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00499 00500 for(ii = 0; ii < 3; ii++) { 00501 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00502 } 00503 00504 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00505 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00506 accel_bias_reg[1] -= (accel_bias[1]/8); 00507 accel_bias_reg[2] -= (accel_bias[2]/8); 00508 00509 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00510 data[1] = (accel_bias_reg[0]) & 0xFF; 00511 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00512 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00513 data[3] = (accel_bias_reg[1]) & 0xFF; 00514 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00515 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00516 data[5] = (accel_bias_reg[2]) & 0xFF; 00517 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00518 00519 // Push accelerometer biases to hardware registers 00520 // writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]); 00521 // writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]); 00522 // writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]); 00523 // writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]); 00524 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]); 00525 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]); 00526 00527 // Output scaled accelerometer biases for manual subtraction in the main program 00528 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00529 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00530 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00531 } 00532 00533 00534 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00535 void MPU6050SelfTest(float * destination) { // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00536 uint8_t rawData[4] = {0, 0, 0, 0}; 00537 uint8_t selfTest[6]; 00538 float factoryTrim[6]; 00539 00540 // Configure the accelerometer for self-test 00541 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g 00542 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00543 wait(0.25); // Delay a while to let the device execute the self-test 00544 rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results 00545 rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results 00546 rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results 00547 rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results 00548 // Extract the acceleration test results first 00549 selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer 00550 selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer 00551 selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer 00552 // Extract the gyration test results first 00553 selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer 00554 selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer 00555 selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer 00556 // Process results to allow final comparison with factory set values 00557 factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation 00558 factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation 00559 factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation 00560 factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation 00561 factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation 00562 factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation 00563 00564 // Output self-test results and factory trim calculation if desired 00565 // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); 00566 // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); 00567 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); 00568 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); 00569 00570 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00571 // To get to percent, must multiply by 100 and subtract result from 100 00572 for (int i = 0; i < 6; i++) { 00573 destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences 00574 } 00575 00576 } 00577 00578 00579 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00580 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00581 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative 00582 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00583 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00584 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00585 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz) { 00586 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00587 float norm; // vector norm 00588 float f1, f2, f3; // objective funcyion elements 00589 float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements 00590 float qDot1, qDot2, qDot3, qDot4; 00591 float hatDot1, hatDot2, hatDot3, hatDot4; 00592 float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error 00593 00594 // Auxiliary variables to avoid repeated arithmetic 00595 float _halfq1 = 0.5f * q1; 00596 float _halfq2 = 0.5f * q2; 00597 float _halfq3 = 0.5f * q3; 00598 float _halfq4 = 0.5f * q4; 00599 float _2q1 = 2.0f * q1; 00600 float _2q2 = 2.0f * q2; 00601 float _2q3 = 2.0f * q3; 00602 float _2q4 = 2.0f * q4; 00603 // float _2q1q3 = 2.0f * q1 * q3; 00604 // float _2q3q4 = 2.0f * q3 * q4; 00605 00606 // Normalise accelerometer measurement 00607 norm = sqrt(ax * ax + ay * ay + az * az); 00608 if (norm == 0.0f) return; // handle NaN 00609 norm = 1.0f/norm; 00610 ax *= norm; 00611 ay *= norm; 00612 az *= norm; 00613 00614 // Compute the objective function and Jacobian 00615 f1 = _2q2 * q4 - _2q1 * q3 - ax; 00616 f2 = _2q1 * q2 + _2q3 * q4 - ay; 00617 f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az; 00618 J_11or24 = _2q3; 00619 J_12or23 = _2q4; 00620 J_13or22 = _2q1; 00621 J_14or21 = _2q2; 00622 J_32 = 2.0f * J_14or21; 00623 J_33 = 2.0f * J_11or24; 00624 00625 // Compute the gradient (matrix multiplication) 00626 hatDot1 = J_14or21 * f2 - J_11or24 * f1; 00627 hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3; 00628 hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1; 00629 hatDot4 = J_14or21 * f1 + J_11or24 * f2; 00630 00631 // Normalize the gradient 00632 norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4); 00633 hatDot1 /= norm; 00634 hatDot2 /= norm; 00635 hatDot3 /= norm; 00636 hatDot4 /= norm; 00637 00638 // Compute estimated gyroscope biases 00639 gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3; 00640 gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2; 00641 gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1; 00642 00643 // Compute and remove gyroscope biases 00644 gbiasx += gerrx * deltat * zeta; 00645 gbiasy += gerry * deltat * zeta; 00646 gbiasz += gerrz * deltat * zeta; 00647 // gx -= gbiasx; 00648 // gy -= gbiasy; 00649 // gz -= gbiasz; 00650 00651 // Compute the quaternion derivative 00652 qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz; 00653 qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy; 00654 qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx; 00655 qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx; 00656 00657 // Compute then integrate estimated quaternion derivative 00658 q1 += (qDot1 -(beta * hatDot1)) * deltat; 00659 q2 += (qDot2 -(beta * hatDot2)) * deltat; 00660 q3 += (qDot3 -(beta * hatDot3)) * deltat; 00661 q4 += (qDot4 -(beta * hatDot4)) * deltat; 00662 00663 // Normalize the quaternion 00664 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00665 norm = 1.0f/norm; 00666 q[0] = q1 * norm; 00667 q[1] = q2 * norm; 00668 q[2] = q3 * norm; 00669 q[3] = q4 * norm; 00670 00671 } 00672 00673 00674 }; 00675 #endif
Generated on Wed Jul 20 2022 08:57:37 by
1.7.2
