main_imu, MPU6050 , racolta_dati sono per il funzionamento dell' accelerometro. my_img_sd è una libreria per gestire i dati su un sd sulla quale vengono forniti solamente le funzioni di lettura e scrittura a blocchi i file trasmetti sono la definizione e implementazione delle funzioni del protoccolo per la gestione dell' invio dei dati con il relativo formato
Dependencies: mbed
MPU6050.h
00001 #ifndef MPU6050_H 00002 #define MPU6050_H 00003 00004 #include "mpu_setting.h" 00005 00006 // Set initial input parameters 00007 enum Ascale { 00008 AFS_2G = 0, 00009 AFS_4G, 00010 AFS_8G, 00011 AFS_16G 00012 }; 00013 00014 enum Gscale { 00015 GFS_250DPS = 0, 00016 GFS_500DPS, 00017 GFS_1000DPS, 00018 GFS_2000DPS 00019 }; 00020 00021 // Specify sensor full scale 00022 int Gscale = GFS_250DPS; 00023 int Ascale = AFS_4G; 00024 00025 //Set up I2C, (SDA,SCL) 00026 00027 //I2C i2c(I2C_SDA, I2C_SCL); 00028 00029 //I2C i2c(PC_9, PA_8); /* setting port i2c imu */ 00030 I2C i2c(PF_0, PF_1); //sda, scl -> usare la 3.3 V 00031 //I2C i2c(PB_9,PB_8); 00032 00033 DigitalOut myled(LED1); 00034 00035 float aRes, gRes; // scale resolutions per LSB for the sensors 00036 00037 // Pin definitions 00038 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 00039 00040 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00041 float ax, ay, az; // Stores the real accel value in g's 00042 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00043 float gx, gy, gz; // Stores the real gyro value in degrees per seconds 00044 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00045 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00046 float temperature; 00047 float SelfTest[6]; 00048 00049 int delt_t = 0; // used to control display output rate 00050 int count = 0; // used to control display output rate 00051 00052 // parameters for 6 DoF sensor fusion calculations 00053 float PI = 3.14159265358979323846f; 00054 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 00055 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00056 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00057 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 00058 float pitch, yaw, roll; 00059 float deltat = 0.0f; // integration interval for both filter schemes 00060 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00061 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00062 00063 class MPU6050 { 00064 00065 protected: 00066 00067 public: 00068 //=================================================================================================================== 00069 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00070 //=================================================================================================================== 00071 00072 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00073 { 00074 char data_write[2]; 00075 data_write[0] = subAddress; 00076 data_write[1] = data; 00077 i2c.write(address, data_write, 2, 0); 00078 } 00079 00080 char readByte(uint8_t address, uint8_t subAddress) 00081 { 00082 char data[1]; // `data` will store the register data 00083 char data_write[1]; 00084 data_write[0] = subAddress; 00085 i2c.write(address, data_write, 1, 1); // no stop 00086 i2c.read(address, data, 1, 0); 00087 return data[0]; 00088 } 00089 00090 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00091 { 00092 char data[14]; 00093 char data_write[1]; 00094 data_write[0] = subAddress; 00095 i2c.write(address, data_write, 1, 1); // no stop 00096 i2c.read(address, data, count, 0); 00097 for(int ii = 0; ii < count; ii++) { 00098 dest[ii] = data[ii]; 00099 } 00100 } 00101 00102 00103 void getGres() { 00104 switch (Gscale) 00105 { 00106 // Possible gyro scales (and their register bit settings) are: 00107 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00108 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00109 case GFS_250DPS: 00110 gRes = 250.0/32768.0; 00111 break; 00112 case GFS_500DPS: 00113 gRes = 500.0/32768.0; 00114 break; 00115 case GFS_1000DPS: 00116 gRes = 1000.0/32768.0; 00117 break; 00118 case GFS_2000DPS: 00119 gRes = 2000.0/32768.0; 00120 break; 00121 } 00122 } 00123 00124 void getAres() { 00125 switch (Ascale) 00126 { 00127 // Possible accelerometer scales (and their register bit settings) are: 00128 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00129 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00130 case AFS_2G: 00131 aRes = 2.0/32768.0; 00132 break; 00133 case AFS_4G: 00134 aRes = 4.0/32768.0; 00135 break; 00136 case AFS_8G: 00137 aRes = 8.0/32768.0; 00138 break; 00139 case AFS_16G: 00140 aRes = 16.0/32768.0; 00141 break; 00142 } 00143 } 00144 00145 00146 void readAccelData(int16_t * destination) 00147 { 00148 uint8_t rawData[6]; // x/y/z accel register data stored here 00149 readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00150 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00151 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00152 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00153 } 00154 00155 void readGyroData(int16_t * destination) 00156 { 00157 uint8_t rawData[6]; // x/y/z gyro register data stored here 00158 readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00159 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00160 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00161 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00162 } 00163 00164 int16_t readTempData() 00165 { 00166 uint8_t rawData[2]; // x/y/z gyro register data stored here 00167 readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00168 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00169 } 00170 00171 00172 00173 // Configure the motion detection control for low power accelerometer mode 00174 void LowPowerAccelOnly() 00175 { 00176 00177 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly 00178 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration 00179 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 00180 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out 00181 // consideration for these threshold evaluations; otherwise, the flags would be set all the time! 00182 00183 uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00184 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6] 00185 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running 00186 00187 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00188 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5] 00189 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running 00190 00191 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00192 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00193 // 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 00194 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter 00195 00196 c = readByte(MPU6050_ADDRESS, CONFIG); 00197 writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0] 00198 writeByte(MPU6050_ADDRESS, CONFIG, c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate 00199 00200 c = readByte(MPU6050_ADDRESS, INT_ENABLE); 00201 writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts 00202 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40); // Enable motion threshold (bits 5) interrupt only 00203 00204 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold 00205 // for at least the counter duration 00206 writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg 00207 writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate 00208 00209 wait(0.1); // Add delay for accumulation of samples 00210 00211 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00212 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00213 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7; hold the initial accleration value as a referance 00214 00215 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00216 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7] 00217 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2]) 00218 00219 c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00220 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5 00221 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts 00222 00223 } 00224 00225 00226 void resetMPU6050() { 00227 // reset device 00228 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00229 wait(0.1); 00230 } 00231 00232 00233 void initMPU6050() 00234 { 00235 // Initialize MPU6050 device 00236 // wake up device 00237 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00238 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00239 00240 // get stable time source 00241 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00242 00243 // Configure Gyro and Accelerometer 00244 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00245 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00246 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00247 writeByte(MPU6050_ADDRESS, CONFIG, 0x03); 00248 00249 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00250 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00251 00252 // Set gyroscope full scale range 00253 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00254 uint8_t c = readByte(MPU6050_ADDRESS, GYRO_CONFIG); 00255 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00256 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00257 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 0); // Set full scale range for the gyro 00258 00259 // Set accelerometer configuration 00260 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00261 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00262 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00263 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 0); // Set full scale range for the accelerometer 00264 00265 // Configure Interrupts and Bypass Enable 00266 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00267 // can join the I2C bus and all can be controlled by the Arduino as master 00268 writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22); 00269 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00270 } 00271 00272 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00273 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00274 void calibrateMPU6050(float * dest1, float * dest2) 00275 { 00276 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00277 uint16_t ii, packet_count, fifo_count; 00278 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00279 00280 // reset device, reset all registers, clear gyro and accelerometer bias registers 00281 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00282 wait_ms(100); 00283 00284 // get stable time source 00285 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00286 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); 00287 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 00288 wait_ms(200); 00289 00290 // Configure device for bias calculation 00291 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00292 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00293 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00294 writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00295 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00296 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00297 wait_ms(20); 00298 00299 // Configure MPU6050 gyro and accelerometer for bias calculation 00300 writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00301 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00302 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00303 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00304 00305 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00306 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00307 00308 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00309 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00310 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050) 00311 wait_us(78250); // accumulate 80 samples in 80 milliseconds = 960 bytes 00312 00313 // At end of sample accumulation, turn off FIFO sensor read 00314 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00315 readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00316 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00317 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00318 // pc.printf("packet = %d", packet_count); 00319 00320 for (ii = 0; ii < packet_count; ii++) { 00321 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00322 readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00323 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00324 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00325 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00326 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00327 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00328 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00329 00330 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00331 accel_bias[1] += (int32_t) accel_temp[1]; 00332 accel_bias[2] += (int32_t) accel_temp[2]; 00333 gyro_bias[0] += (int32_t) gyro_temp[0]; 00334 gyro_bias[1] += (int32_t) gyro_temp[1]; 00335 gyro_bias[2] += (int32_t) gyro_temp[2]; 00336 00337 } 00338 00339 pc.printf("packet = %d, filo = %d", packet_count,fifo_count); 00340 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00341 accel_bias[1] /= (int32_t) packet_count; 00342 accel_bias[2] /= (int32_t) packet_count; 00343 gyro_bias[0] /= (int32_t) packet_count; 00344 gyro_bias[1] /= (int32_t) packet_count; 00345 gyro_bias[2] /= (int32_t) packet_count; 00346 00347 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00348 else {accel_bias[2] += (int32_t) accelsensitivity;} 00349 00350 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00351 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 00352 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00353 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00354 data[3] = (-gyro_bias[1]/4) & 0xFF; 00355 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00356 data[5] = (-gyro_bias[2]/4) & 0xFF; 00357 00358 // Push gyro biases to hardware registers 00359 writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 00360 writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); 00361 writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); 00362 writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); 00363 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); 00364 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); 00365 00366 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00367 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00368 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00369 00370 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00371 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00372 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00373 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00374 // the accelerometer biases calculated above must be divided by 8. 00375 00376 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00377 readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00378 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00379 readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00380 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00381 readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00382 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00383 00384 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00385 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00386 00387 for(ii = 0; ii < 3; ii++) { 00388 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00389 } 00390 00391 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00392 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00393 accel_bias_reg[1] -= (accel_bias[1]/8); 00394 accel_bias_reg[2] -= (accel_bias[2]/8); 00395 00396 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00397 data[1] = (accel_bias_reg[0]) & 0xFF; 00398 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00399 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00400 data[3] = (accel_bias_reg[1]) & 0xFF; 00401 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00402 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00403 data[5] = (accel_bias_reg[2]) & 0xFF; 00404 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00405 00406 // Push accelerometer biases to hardware registers 00407 // writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]); 00408 // writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]); 00409 // writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]); 00410 // writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]); 00411 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]); 00412 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]); 00413 00414 // Output scaled accelerometer biases for manual subtraction in the main program 00415 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00416 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00417 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00418 printf("set acc : x= %f\t,y= %f\tz= %f\r\n;",accelBias[0],accelBias[1],accelBias[2]); 00419 00420 } 00421 00422 00423 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00424 void MPU6050SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00425 { 00426 uint8_t rawData[4] = {0, 0, 0, 0}; 00427 uint8_t selfTest[6]; 00428 float factoryTrim[6]; 00429 00430 // Configure the accelerometer for self-test 00431 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g 00432 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00433 wait(0.25); // Delay a while to let the device execute the self-test 00434 rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results 00435 rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results 00436 rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results 00437 rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results 00438 // Extract the acceleration test results first 00439 selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer 00440 selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer 00441 selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer 00442 // Extract the gyration test results first 00443 selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer 00444 selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer 00445 selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer 00446 // Process results to allow final comparison with factory set values 00447 factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation 00448 factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation 00449 factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation 00450 factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation 00451 factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation 00452 factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation 00453 00454 // Output self-test results and factory trim calculation if desired 00455 // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); 00456 // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); 00457 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); 00458 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); 00459 00460 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00461 // To get to percent, must multiply by 100 and subtract result from 100 00462 for (int i = 0; i < 6; i++) { 00463 destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences 00464 } 00465 00466 } 00467 00468 00469 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00470 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00471 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative 00472 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00473 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00474 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00475 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz) 00476 { 00477 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00478 float norm; // vector norm 00479 float f1, f2, f3; // objective funcyion elements 00480 float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements 00481 float qDot1, qDot2, qDot3, qDot4; 00482 float hatDot1, hatDot2, hatDot3, hatDot4; 00483 float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error 00484 00485 // Auxiliary variables to avoid repeated arithmetic 00486 float _halfq1 = 0.5f * q1; 00487 float _halfq2 = 0.5f * q2; 00488 float _halfq3 = 0.5f * q3; 00489 float _halfq4 = 0.5f * q4; 00490 float _2q1 = 2.0f * q1; 00491 float _2q2 = 2.0f * q2; 00492 float _2q3 = 2.0f * q3; 00493 float _2q4 = 2.0f * q4; 00494 // float _2q1q3 = 2.0f * q1 * q3; 00495 // float _2q3q4 = 2.0f * q3 * q4; 00496 00497 // Normalise accelerometer measurement 00498 norm = sqrt(ax * ax + ay * ay + az * az); 00499 if (norm == 0.0f) return; // handle NaN 00500 norm = 1.0f/norm; 00501 ax *= norm; 00502 ay *= norm; 00503 az *= norm; 00504 00505 // Compute the objective function and Jacobian 00506 f1 = _2q2 * q4 - _2q1 * q3 - ax; 00507 f2 = _2q1 * q2 + _2q3 * q4 - ay; 00508 f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az; 00509 J_11or24 = _2q3; 00510 J_12or23 = _2q4; 00511 J_13or22 = _2q1; 00512 J_14or21 = _2q2; 00513 J_32 = 2.0f * J_14or21; 00514 J_33 = 2.0f * J_11or24; 00515 00516 // Compute the gradient (matrix multiplication) 00517 hatDot1 = J_14or21 * f2 - J_11or24 * f1; 00518 hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3; 00519 hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1; 00520 hatDot4 = J_14or21 * f1 + J_11or24 * f2; 00521 00522 // Normalize the gradient 00523 norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4); 00524 hatDot1 /= norm; 00525 hatDot2 /= norm; 00526 hatDot3 /= norm; 00527 hatDot4 /= norm; 00528 00529 // Compute estimated gyroscope biases 00530 gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3; 00531 gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2; 00532 gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1; 00533 00534 // Compute and remove gyroscope biases 00535 gbiasx += gerrx * deltat * zeta; 00536 gbiasy += gerry * deltat * zeta; 00537 gbiasz += gerrz * deltat * zeta; 00538 // gx -= gbiasx; 00539 // gy -= gbiasy; 00540 // gz -= gbiasz; 00541 00542 // Compute the quaternion derivative 00543 qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz; 00544 qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy; 00545 qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx; 00546 qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx; 00547 00548 // Compute then integrate estimated quaternion derivative 00549 q1 += (qDot1 -(beta * hatDot1)) * deltat; 00550 q2 += (qDot2 -(beta * hatDot2)) * deltat; 00551 q3 += (qDot3 -(beta * hatDot3)) * deltat; 00552 q4 += (qDot4 -(beta * hatDot4)) * deltat; 00553 00554 // Normalize the quaternion 00555 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00556 norm = 1.0f/norm; 00557 q[0] = q1 * norm; 00558 q[1] = q2 * norm; 00559 q[2] = q3 * norm; 00560 q[3] = q4 * norm; 00561 00562 } 00563 00564 void calibrate_manual_MPU6050(float * dest1, float * dest2){ 00565 //giroscopio 00566 dest1[0] = 0;//(float) gyro_bias[0]/(float) gyrosensitivity; 00567 dest1[1] =0;// ((float) gyro_bias[1]/(float) gyrosensitivity; 00568 dest1[2] = 0;//(float) gyro_bias[2]/(float) gyrosensitivity; 00569 00570 //acceletomtro 00571 dest2[0] = 0;//(float)accel_bias[0]/(float)accelsensitivity; 00572 dest2[1] = 0;//float)accel_bias[1]/(float)accelsensitivity; 00573 dest2[2] = 0;//(float)accel_bias[2]/(float)accelsensitivity; 00574 00575 00576 } 00577 00578 00579 }; 00580 #endif
Generated on Sun Jul 17 2022 15:08:00 by 1.7.2