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.
main.cpp
00001 #include "mbed.h" 00002 #include "mbed_events.h" 00003 #include "MPU9250.h" 00004 00005 DigitalOut led1(LED1); 00006 InterruptIn sw(USER_BUTTON); 00007 00008 Thread eventthread; 00009 Thread imuthread; 00010 bool read_imu_isrunning; 00011 00012 00013 // Pin defines 00014 DigitalOut led_green(D4); 00015 00016 //----------------------------------------------------- 00017 //IMU 00018 float sum = 0; 00019 uint32_t sumCount = 0; 00020 char buffer[14]; 00021 00022 MPU9250 mpu9250; 00023 Timer t; 00024 Serial pc(USBTX, USBRX); // tx, rx 00025 //----------------------------------------------------- 00026 00027 void rise_handler(void) 00028 { 00029 printf("rise_handler in context %p\r\n", Thread::gettid()); 00030 // Toggle LED 00031 led1 = !led1; 00032 for (int i = 0; i<10; i++) { 00033 led_green = !led_green; 00034 wait(0.5); 00035 } 00036 } 00037 00038 void fall_handler(void) 00039 { 00040 printf("fall_handler in context %p\r\n", Thread::gettid()); 00041 // Toggle LED 00042 led1 = !led1; 00043 } 00044 00045 void readIMU() 00046 { 00047 while(read_imu_isrunning) { 00048 pc.printf("in thread readIMU\n\r"); 00049 // If intPin goes high, all data registers have new data 00050 if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 00051 00052 mpu9250.readAccelData(accelCount); // Read the x/y/z adc values 00053 // Now we'll calculate the accleration value into actual g's 00054 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set 00055 ay = (float)accelCount[1]*aRes - accelBias[1]; 00056 az = (float)accelCount[2]*aRes - accelBias[2]; 00057 00058 mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values 00059 // Calculate the gyro value into actual degrees per second 00060 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set 00061 gy = (float)gyroCount[1]*gRes - gyroBias[1]; 00062 gz = (float)gyroCount[2]*gRes - gyroBias[2]; 00063 00064 mpu9250.readMagData(magCount); // Read the x/y/z adc values 00065 // Calculate the magnetometer values in milliGauss 00066 // Include factory calibration per data sheet and user environmental corrections 00067 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set 00068 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 00069 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 00070 } 00071 00072 Now = t.read_us(); 00073 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00074 lastUpdate = Now; 00075 00076 sum += deltat; 00077 sumCount++; 00078 00079 // if(lastUpdate - firstUpdate > 10000000.0f) { 00080 // beta = 0.04; // decrease filter gain after stabilized 00081 // zeta = 0.015; // increasey bias drift gain after stabilized 00082 // } 00083 00084 // Pass gyro rate as rad/s 00085 mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00086 //mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00087 00088 // Serial print and/or display at 0.5 s rate independent of data rates 00089 delt_t = t.read_ms() - _count; 00090 if (delt_t > 50) { // update LCD once per half-second independent of read rate 00091 00092 /*pc.printf("ax = %f", 1000*ax); 00093 pc.printf(" ay = %f", 1000*ay); 00094 pc.printf(" az = %f mg\n\r", 1000*az); 00095 00096 pc.printf("gx = %f", gx); 00097 pc.printf(" gy = %f", gy); 00098 pc.printf(" gz = %f deg/s\n\r", gz); 00099 00100 pc.printf("gx = %f", mx); 00101 pc.printf(" gy = %f", my); 00102 pc.printf(" gz = %f mG\n\r", mz);*/ 00103 00104 tempCount = mpu9250.readTempData(); // Read the adc values 00105 temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade 00106 //pc.printf(" temperature = %f C\n\r", temperature); 00107 00108 /*pc.printf("q0 = %f\n\r", q[0]); 00109 pc.printf("q1 = %f\n\r", q[1]); 00110 pc.printf("q2 = %f\n\r", q[2]); 00111 pc.printf("q3 = %f\n\r", q[3]);*/ 00112 00113 /* lcd.clear(); 00114 lcd.printString("MPU9250", 0, 0); 00115 lcd.printString("x y z", 0, 1); 00116 sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az)); 00117 lcd.printString(buffer, 0, 2); 00118 sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz); 00119 lcd.printString(buffer, 0, 3); 00120 sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz); 00121 lcd.printString(buffer, 0, 4); 00122 */ 00123 // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 00124 // In this coordinate system, the positive z-axis is down toward Earth. 00125 // 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. 00126 // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 00127 // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 00128 // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 00129 // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 00130 // applied in the correct order which for this configuration is yaw, pitch, and then roll. 00131 // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 00132 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]); 00133 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00134 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]); 00135 pitch *= 180.0f / PI; 00136 yaw *= 180.0f / PI; 00137 yaw -= 2.93f; // Declination at 8572 Berg TG: +2° 56' 00138 roll *= 180.0f / PI; 00139 00140 pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll); 00141 //pc.printf("average rate = %f\n\r", (float) sumCount/sum); 00142 // sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll); 00143 // lcd.printString(buffer, 0, 4); 00144 // sprintf(buffer, "rate = %f", (float) sumCount/sum); 00145 // lcd.printString(buffer, 0, 5); 00146 00147 myled= !myled; 00148 _count = t.read_ms(); 00149 00150 if(_count > 1<<21) { 00151 t.start(); // start the timer over again if ~30 minutes has passed 00152 _count = 0; 00153 deltat= 0; 00154 lastUpdate = t.read_us(); 00155 } 00156 sum = 0; 00157 sumCount = 0; 00158 } 00159 } 00160 } 00161 00162 void imuSetup() 00163 { 00164 read_imu_isrunning = true; 00165 //Set up I2C 00166 i2c.frequency(400000); // use fast (400 kHz) I2C 00167 00168 pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); 00169 00170 t.start(); 00171 // lcd.setBrightness(0.05); 00172 00173 00174 // Read the WHO_AM_I register, this is a good test of communication 00175 uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 00176 pc.printf("I AM 0x%x\n\r", whoami); 00177 pc.printf("I SHOULD BE 0x71\n\r"); 00178 00179 if (whoami == 0x71) { // WHO_AM_I should always be 0x68 00180 pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami); 00181 pc.printf("MPU9250 is online...\n\r"); 00182 sprintf(buffer, "0x%x", whoami); 00183 wait(1); 00184 00185 mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration 00186 mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values 00187 pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]); 00188 pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]); 00189 pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]); 00190 pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]); 00191 pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]); 00192 pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]); 00193 mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00194 pc.printf("x gyro bias = %f\n\r", gyroBias[0]); 00195 pc.printf("y gyro bias = %f\n\r", gyroBias[1]); 00196 pc.printf("z gyro bias = %f\n\r", gyroBias[2]); 00197 pc.printf("x accel bias = %f\n\r", accelBias[0]); 00198 pc.printf("y accel bias = %f\n\r", accelBias[1]); 00199 pc.printf("z accel bias = %f\n\r", accelBias[2]); 00200 wait(2); 00201 mpu9250.initMPU9250(); 00202 pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00203 mpu9250.initAK8963(magCalibration); 00204 pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer 00205 pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale)); 00206 pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale)); 00207 if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r"); 00208 if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r"); 00209 if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r"); 00210 if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r"); 00211 wait(1); 00212 } else { 00213 pc.printf("Could not connect to MPU9250: \n\r"); 00214 pc.printf("%#x \n", whoami); 00215 sprintf(buffer, "WHO_AM_I 0x%x", whoami); 00216 00217 while(1) { 00218 // Loop forever if communication doesn't happen 00219 pc.printf("commication not happening\n\r"); 00220 } 00221 } 00222 00223 mpu9250.getAres(); // Get accelerometer sensitivity 00224 mpu9250.getGres(); // Get gyro sensitivity 00225 mpu9250.getMres(); // Get magnetometer sensitivity 00226 pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes); 00227 pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes); 00228 pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes); 00229 magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated 00230 magbias[1] = +120.; // User environmental x-axis correction in milliGauss 00231 magbias[2] = +125.; // User environmental x-axis correction in milliGauss 00232 } 00233 00234 00235 int main() 00236 { 00237 pc.baud(9600); 00238 imuSetup(); 00239 imuthread.start(readIMU); 00240 00241 // Request the shared queue 00242 EventQueue *queue = mbed_event_queue(); 00243 printf("Starting in context %p\r\n", Thread::gettid()); 00244 00245 // The 'rise' handler will execute in IRQ context 00246 sw.rise(queue->event(rise_handler)); 00247 // The 'fall' handler will execute in the context of the shared queue (actually the main thread) 00248 sw.fall(queue->event(fall_handler)); 00249 // Setup complete, so we now dispatch the shared queue from main 00250 queue->dispatch_forever(); 00251 }
Generated on Sun Dec 4 2022 15:54:31 by
1.7.2