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