programma di test per vedere se funziona
Dependencies: SDFileSystem_conMOD mbed-rtos mbed
Fork of f4_sd_imu_4 by
accellerometro.h
00001 #ifndef __ACCELLEROMETRO__ 00002 #define __ACCELLEROMETRO__ 00003 00004 #include "MPU6050.h" 00005 #include "setting.h" 00006 00007 00008 float sum = 0; 00009 uint32_t sumCount = 0; 00010 00011 MPU6050 mpu6050; 00012 00013 Timer t; 00014 00015 void initAccellerometro(){ 00016 t.start(); 00017 00018 i2c.frequency(400000); 00019 uint8_t whoami = mpu6050.readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Read WHO_AM_I register for MPU-6050 //DEBUG 00020 pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x68\n\r"); //DEBUG 00021 00022 if (whoami == 0x68){ 00023 pc.printf("MPU6050 is online..."); 00024 wait(1); 00025 00026 mpu6050.MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values 00027 pc.printf("x-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[0]); pc.printf("% of factory value \n\r"); 00028 pc.printf("y-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[1]); pc.printf("% of factory value \n\r"); 00029 pc.printf("z-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[2]); pc.printf("% of factory value \n\r"); 00030 pc.printf("x-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[3]); pc.printf("% of factory value \n\r"); 00031 pc.printf("y-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[4]); pc.printf("% of factory value \n\r"); 00032 pc.printf("z-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[5]); pc.printf("% of factory value \n\r"); 00033 wait(1); 00034 00035 if(SelfTest[0] < 1.0f && SelfTest[1] < 1.0f && SelfTest[2] < 1.0f && SelfTest[3] < 1.0f && SelfTest[4] < 1.0f && SelfTest[5] < 1.0f) { 00036 mpu6050.resetMPU6050(); // Reset registers to default in preparation for device calibration 00037 mpu6050.calibrateMPU6050(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00038 mpu6050.initMPU6050(); pc.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00039 00040 wait(2); 00041 } 00042 else{ 00043 pc.printf("Device did not the pass self-test!\n\r"); 00044 } 00045 } 00046 else{ 00047 pc.printf("Could not connect to MPU6050: \n\r"); 00048 pc.printf("%#x \n", whoami); 00049 00050 while(1) ; // Loop forever if communication doesn't happen 00051 } 00052 } 00053 00054 void raccoltaDati(){ 00055 if(mpu6050.readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { // check if data ready interrupt 00056 mpu6050.readAccelData(accelCount); // Read the x/y/z adc values 00057 mpu6050.getAres(); 00058 00059 // Now we'll calculate the accleration value into actual g's 00060 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set 00061 ay = (float)accelCount[1]*aRes - accelBias[1]; 00062 az = (float)accelCount[2]*aRes - accelBias[2]; 00063 00064 fprintf(fp,"A%03.0f%03.0f%03.0f\n\r", 100*ax+400, 100*ay+400, 100*az+400); 00065 00066 00067 mpu6050.readGyroData(gyroCount); // Read the x/y/z adc values 00068 mpu6050.getGres(); 00069 00070 // Calculate the gyro value into actual degrees per second 00071 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set 00072 gy = (float)gyroCount[1]*gRes; // - gyroBias[1]; 00073 gz = (float)gyroCount[2]*gRes; // - gyroBias[2]; 00074 00075 00076 invia_m(1000*ax+4000,1000*ay+4000,1000*az+4000,0,0,0); 00077 tempCount = mpu6050.readTempData(); // Read the x/y/z adc values 00078 temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade 00079 } 00080 00081 Now = t.read_us(); 00082 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00083 lastUpdate = Now; 00084 00085 sum += deltat; 00086 sumCount++; 00087 00088 if(lastUpdate - firstUpdate > 10000000.0f) { 00089 beta = 0.04; // decrease filter gain after stabilized 00090 zeta = 0.015; // increasey bias drift gain after stabilized 00091 } 00092 00093 // Pass gyro rate as rad/s 00094 mpu6050.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f); 00095 00096 // Serial print and/or display at 0.5 s rate independent of data rates 00097 delt_t = t.read_ms() - count; 00098 if (delt_t > 500) { // update LCD once per half-second independent of read rate 00099 /* 00100 pc.printf("ax = %f", 1000*ax); 00101 pc.printf(" ay = %f", 1000*ay); 00102 pc.printf(" az = %f mg\n\r", 1000*az); 00103 00104 pc.printf("gx = %f", gx); 00105 pc.printf(" gy = %f", gy); 00106 pc.printf(" gz = %f deg/s\n\r", gz); 00107 00108 pc.printf(" temperature = %f C\n\r", temperature); 00109 00110 pc.printf("q0 = %f\n\r", q[0]); 00111 pc.printf("q1 = %f\n\r", q[1]); 00112 pc.printf("q2 = %f\n\r", q[2]); 00113 pc.printf("q3 = %f\n\r", q[3]); 00114 */ 00115 00116 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 00117 // In this coordinate system, the positive z-axis is down toward Earth. 00118 // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 00119 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 00120 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 00121 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 00122 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 00123 // applied in the correct order which for this configuration is yaw, pitch, and then roll. 00124 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 00125 yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); 00126 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00127 roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); 00128 pitch *= 180.0f / PI; 00129 yaw *= 180.0f / PI; 00130 roll *= 180.0f / PI; 00131 00132 /* 00133 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll); 00134 pc.printf("average rate = %f\n\r", (float) sumCount/sum); 00135 */ 00136 00137 count = t.read_ms(); 00138 sum = 0; 00139 sumCount = 0; 00140 } 00141 } 00142 00143 00144 00145 #endif
Generated on Thu Jul 14 2022 13:03:23 by
1.7.2
