Panusorn Chinsakuljaroen
/
BTL432kc
imu for l432kc
BTL432KC.cpp@4:7b04752df27f, 2018-12-08 (annotated)
- Committer:
- sunninety1
- Date:
- Sat Dec 08 05:48:54 2018 +0000
- Revision:
- 4:7b04752df27f
- Parent:
- 3:4a1bc31c360f
for l432kc;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
sunninety1 | 3:4a1bc31c360f | 1 | /* MPU9250 Basic Example Code |
sunninety1 | 3:4a1bc31c360f | 2 | by: Kris Winer |
sunninety1 | 3:4a1bc31c360f | 3 | date: April 1, 2014 |
sunninety1 | 3:4a1bc31c360f | 4 | license: Beerware - Use this code however you'd like. If you |
sunninety1 | 3:4a1bc31c360f | 5 | find it useful you can buy me a beer some time. |
sunninety1 | 2:01ca44dd3908 | 6 | |
sunninety1 | 3:4a1bc31c360f | 7 | Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor, |
sunninety1 | 3:4a1bc31c360f | 8 | getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to |
sunninety1 | 3:4a1bc31c360f | 9 | allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and |
sunninety1 | 3:4a1bc31c360f | 10 | Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. |
sunninety1 | 2:01ca44dd3908 | 11 | |
sunninety1 | 3:4a1bc31c360f | 12 | SDA and SCL should have external pull-up resistors (to 3.3V). |
sunninety1 | 3:4a1bc31c360f | 13 | 10k resistors are on the EMSENSR-9250 breakout board. |
sunninety1 | 3:4a1bc31c360f | 14 | |
sunninety1 | 3:4a1bc31c360f | 15 | Hardware setup: |
sunninety1 | 3:4a1bc31c360f | 16 | MPU9250 Breakout --------- Arduino |
sunninety1 | 3:4a1bc31c360f | 17 | VDD ---------------------- 3.3V |
sunninety1 | 3:4a1bc31c360f | 18 | VDDI --------------------- 3.3V |
sunninety1 | 3:4a1bc31c360f | 19 | SDA ----------------------- A4 |
sunninety1 | 3:4a1bc31c360f | 20 | SCL ----------------------- A5 |
sunninety1 | 3:4a1bc31c360f | 21 | GND ---------------------- GND |
sunninety1 | 3:4a1bc31c360f | 22 | |
sunninety1 | 3:4a1bc31c360f | 23 | Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library. |
sunninety1 | 3:4a1bc31c360f | 24 | Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. |
sunninety1 | 3:4a1bc31c360f | 25 | We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file. |
sunninety1 | 3:4a1bc31c360f | 26 | We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file. |
sunninety1 | 3:4a1bc31c360f | 27 | */ |
sunninety1 | 3:4a1bc31c360f | 28 | |
sunninety1 | 3:4a1bc31c360f | 29 | //#include "ST_F401_84MHZ.h" |
sunninety1 | 3:4a1bc31c360f | 30 | //F401_init84 myinit(0); |
sunninety1 | 2:01ca44dd3908 | 31 | #include "mbed.h" |
sunninety1 | 3:4a1bc31c360f | 32 | #include "MPU9250.h" |
sunninety1 | 3:4a1bc31c360f | 33 | |
sunninety1 | 3:4a1bc31c360f | 34 | // Using NOKIA 5110 monochrome 84 x 48 pixel display |
sunninety1 | 3:4a1bc31c360f | 35 | // pin 9 - Serial clock out (SCLK) |
sunninety1 | 3:4a1bc31c360f | 36 | // pin 8 - Serial data out (DIN) |
sunninety1 | 3:4a1bc31c360f | 37 | // pin 7 - Data/Command select (D/C) |
sunninety1 | 3:4a1bc31c360f | 38 | // pin 5 - LCD chip select (CS) |
sunninety1 | 3:4a1bc31c360f | 39 | // pin 6 - LCD reset (RST) |
sunninety1 | 3:4a1bc31c360f | 40 | //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6); |
sunninety1 | 3:4a1bc31c360f | 41 | |
sunninety1 | 3:4a1bc31c360f | 42 | float sum = 0; |
sunninety1 | 3:4a1bc31c360f | 43 | uint32_t sumCount = 0; |
sunninety1 | 3:4a1bc31c360f | 44 | char buffer[14]; |
sunninety1 | 3:4a1bc31c360f | 45 | |
sunninety1 | 3:4a1bc31c360f | 46 | MPU9250 mpu9250; |
sunninety1 | 3:4a1bc31c360f | 47 | |
sunninety1 | 2:01ca44dd3908 | 48 | Timer t; |
sunninety1 | 2:01ca44dd3908 | 49 | |
sunninety1 | 3:4a1bc31c360f | 50 | Serial serial(PA_9,PA_10); |
sunninety1 | 3:4a1bc31c360f | 51 | Serial pc(USBTX, USBRX); // tx, rx |
sunninety1 | 3:4a1bc31c360f | 52 | |
sunninety1 | 3:4a1bc31c360f | 53 | // VCC, SCE, RST, D/C, MOSI,S CLK, LED |
sunninety1 | 2:01ca44dd3908 | 54 | |
sunninety1 | 3:4a1bc31c360f | 55 | //DigitalIn boardbtn(USER_BUTTON); |
sunninety1 | 3:4a1bc31c360f | 56 | static float acc_xyz[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 57 | static float v_xyz[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 58 | float displacement_body[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 59 | static float displacement_world[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 60 | void AccelToVelocity(float ax,float ay,float az,float dt){ |
sunninety1 | 3:4a1bc31c360f | 61 | static float old_acc[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 62 | static float old_v[3]={0,0,0}; |
sunninety1 | 3:4a1bc31c360f | 63 | float delta_ax=ax-old_acc[0]; |
sunninety1 | 3:4a1bc31c360f | 64 | float delta_ay=ay-old_acc[1]; |
sunninety1 | 3:4a1bc31c360f | 65 | float delta_az=az-old_acc[2]; |
sunninety1 | 3:4a1bc31c360f | 66 | old_acc[0]=ax; |
sunninety1 | 3:4a1bc31c360f | 67 | old_acc[1]=ay; |
sunninety1 | 3:4a1bc31c360f | 68 | old_acc[2]=az; |
sunninety1 | 3:4a1bc31c360f | 69 | old_v[0]=v_xyz[0]-old_v[0]; |
sunninety1 | 3:4a1bc31c360f | 70 | old_v[1]=v_xyz[1]-old_v[1]; |
sunninety1 | 3:4a1bc31c360f | 71 | old_v[2]=v_xyz[2]-old_v[2]; |
sunninety1 | 3:4a1bc31c360f | 72 | v_xyz[0]+=ax*dt; |
sunninety1 | 3:4a1bc31c360f | 73 | v_xyz[1]+=ay*dt; |
sunninety1 | 3:4a1bc31c360f | 74 | v_xyz[2]+=az*dt; |
sunninety1 | 2:01ca44dd3908 | 75 | |
sunninety1 | 3:4a1bc31c360f | 76 | |
sunninety1 | 3:4a1bc31c360f | 77 | displacement_body[0]+=v_xyz[0]*dt; |
sunninety1 | 3:4a1bc31c360f | 78 | displacement_body[1]+=v_xyz[1]*dt; |
sunninety1 | 3:4a1bc31c360f | 79 | displacement_body[2]+=v_xyz[2]*dt; |
sunninety1 | 3:4a1bc31c360f | 80 | // pc.printf("%f\n",dt); |
sunninety1 | 3:4a1bc31c360f | 81 | /*displacement_body[0]+=fillter_vx*dt; |
sunninety1 | 3:4a1bc31c360f | 82 | displacement_body[1]+=fillter_vy*dt; |
sunninety1 | 3:4a1bc31c360f | 83 | displacement_body[2]+=fillter_vz*dt;*/ |
sunninety1 | 3:4a1bc31c360f | 84 | |
sunninety1 | 2:01ca44dd3908 | 85 | } |
sunninety1 | 3:4a1bc31c360f | 86 | /*void VelocityToDisplacement(float dt){ |
sunninety1 | 3:4a1bc31c360f | 87 | displacement_body[0]+=v_xyz[0]*dt; |
sunninety1 | 3:4a1bc31c360f | 88 | displacement_body[1]+=v_xyz[1]*dt; |
sunninety1 | 3:4a1bc31c360f | 89 | displacement_body[2]+=v_xyz[2]*dt; |
sunninety1 | 3:4a1bc31c360f | 90 | |
sunninety1 | 2:01ca44dd3908 | 91 | }*/ |
sunninety1 | 2:01ca44dd3908 | 92 | int main() |
sunninety1 | 3:4a1bc31c360f | 93 | { |
sunninety1 | 2:01ca44dd3908 | 94 | pc.baud(115200); |
sunninety1 | 3:4a1bc31c360f | 95 | |
sunninety1 | 3:4a1bc31c360f | 96 | //Set up I2C |
sunninety1 | 3:4a1bc31c360f | 97 | i2c.frequency(400000); // use fast (400 kHz) I2C |
sunninety1 | 3:4a1bc31c360f | 98 | |
sunninety1 | 3:4a1bc31c360f | 99 | // pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); |
sunninety1 | 3:4a1bc31c360f | 100 | |
sunninety1 | 2:01ca44dd3908 | 101 | t.start(); |
sunninety1 | 3:4a1bc31c360f | 102 | |
sunninety1 | 3:4a1bc31c360f | 103 | |
sunninety1 | 3:4a1bc31c360f | 104 | |
sunninety1 | 3:4a1bc31c360f | 105 | |
sunninety1 | 3:4a1bc31c360f | 106 | // Read the WHO_AM_I register, this is a good test of communication |
sunninety1 | 3:4a1bc31c360f | 107 | uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 |
sunninety1 | 3:4a1bc31c360f | 108 | // pc.printf("I AM 0x%x\n\r", whoami); |
sunninety1 | 3:4a1bc31c360f | 109 | // pc.printf("I SHOULD BE 0x71\n\r"); |
sunninety1 | 3:4a1bc31c360f | 110 | |
sunninety1 | 3:4a1bc31c360f | 111 | if (whoami == 0x71) { // WHO_AM_I should always be 0x68 |
sunninety1 | 3:4a1bc31c360f | 112 | // pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami); |
sunninety1 | 3:4a1bc31c360f | 113 | // pc.printf("MPU9250 is online...\n\r"); |
sunninety1 | 3:4a1bc31c360f | 114 | |
sunninety1 | 3:4a1bc31c360f | 115 | // sprintf(buffer, "0x%x", whoami); |
sunninety1 | 3:4a1bc31c360f | 116 | |
sunninety1 | 3:4a1bc31c360f | 117 | wait(1); |
sunninety1 | 3:4a1bc31c360f | 118 | |
sunninety1 | 3:4a1bc31c360f | 119 | mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration |
sunninety1 | 3:4a1bc31c360f | 120 | mpu9250.MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values |
sunninety1 | 3:4a1bc31c360f | 121 | /* pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]); |
sunninety1 | 3:4a1bc31c360f | 122 | pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]); |
sunninety1 | 3:4a1bc31c360f | 123 | pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]); |
sunninety1 | 3:4a1bc31c360f | 124 | pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]); |
sunninety1 | 3:4a1bc31c360f | 125 | pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]); |
sunninety1 | 3:4a1bc31c360f | 126 | pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);*/ |
sunninety1 | 3:4a1bc31c360f | 127 | // if(boardbtn==0){ |
sunninety1 | 3:4a1bc31c360f | 128 | // wait(2); |
sunninety1 | 3:4a1bc31c360f | 129 | mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers |
sunninety1 | 3:4a1bc31c360f | 130 | pc.printf("x gyro bias = %f\n\r", gyroBias[0]); |
sunninety1 | 3:4a1bc31c360f | 131 | pc.printf("y gyro bias = %f\n\r", gyroBias[1]); |
sunninety1 | 3:4a1bc31c360f | 132 | pc.printf("z gyro bias = %f\n\r", gyroBias[2]); |
sunninety1 | 3:4a1bc31c360f | 133 | pc.printf("x accel bias = %f\n\r", accelBias[0]); |
sunninety1 | 3:4a1bc31c360f | 134 | pc.printf("y accel bias = %f\n\r", accelBias[1]); |
sunninety1 | 3:4a1bc31c360f | 135 | pc.printf("z accel bias = %f\n\r", accelBias[2]); |
sunninety1 | 3:4a1bc31c360f | 136 | wait(2); |
sunninety1 | 3:4a1bc31c360f | 137 | |
sunninety1 | 3:4a1bc31c360f | 138 | /* |
sunninety1 | 3:4a1bc31c360f | 139 | // ----------------------------------------------------------------- |
sunninety1 | 3:4a1bc31c360f | 140 | }else{ |
sunninety1 | 3:4a1bc31c360f | 141 | gyroBias[0]=-1.244275; |
sunninety1 | 3:4a1bc31c360f | 142 | gyroBias[1]=0.122137; |
sunninety1 | 3:4a1bc31c360f | 143 | gyroBias[2]=-0.717557; |
sunninety1 | 3:4a1bc31c360f | 144 | accelBias[0]=0.007996; // For Manual Calibate with button |
sunninety1 | 3:4a1bc31c360f | 145 | accelBias[1]=0.021240; |
sunninety1 | 3:4a1bc31c360f | 146 | accelBias[2]=-0.020508; |
sunninety1 | 3:4a1bc31c360f | 147 | } |
sunninety1 | 3:4a1bc31c360f | 148 | //------------------------------------------------------------------ |
sunninety1 | 3:4a1bc31c360f | 149 | */ |
sunninety1 | 3:4a1bc31c360f | 150 | mpu9250.initMPU9250(); |
sunninety1 | 3:4a1bc31c360f | 151 | // pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature |
sunninety1 | 3:4a1bc31c360f | 152 | mpu9250.initAK8963(magCalibration); |
sunninety1 | 3:4a1bc31c360f | 153 | /* pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer |
sunninety1 | 3:4a1bc31c360f | 154 | pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale)); |
sunninety1 | 3:4a1bc31c360f | 155 | pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale)); |
sunninety1 | 3:4a1bc31c360f | 156 | if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r"); |
sunninety1 | 3:4a1bc31c360f | 157 | if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r"); |
sunninety1 | 3:4a1bc31c360f | 158 | if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r"); |
sunninety1 | 3:4a1bc31c360f | 159 | if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r"); |
sunninety1 | 3:4a1bc31c360f | 160 | wait(1); |
sunninety1 | 3:4a1bc31c360f | 161 | */ |
sunninety1 | 3:4a1bc31c360f | 162 | } else { |
sunninety1 | 3:4a1bc31c360f | 163 | pc.printf("Could not connect to MPU9250: \n\r"); |
sunninety1 | 3:4a1bc31c360f | 164 | pc.printf("%#x \n", whoami); |
sunninety1 | 3:4a1bc31c360f | 165 | |
sunninety1 | 3:4a1bc31c360f | 166 | |
sunninety1 | 3:4a1bc31c360f | 167 | sprintf(buffer, "WHO_AM_I 0x%x", whoami); |
sunninety1 | 3:4a1bc31c360f | 168 | |
sunninety1 | 3:4a1bc31c360f | 169 | |
sunninety1 | 3:4a1bc31c360f | 170 | while(1) ; // Loop forever if communication doesn't happen |
sunninety1 | 3:4a1bc31c360f | 171 | |
sunninety1 | 3:4a1bc31c360f | 172 | } |
sunninety1 | 3:4a1bc31c360f | 173 | |
sunninety1 | 3:4a1bc31c360f | 174 | mpu9250.getAres(); // Get accelerometer sensitivity |
sunninety1 | 3:4a1bc31c360f | 175 | mpu9250.getGres(); // Get gyro sensitivity |
sunninety1 | 3:4a1bc31c360f | 176 | mpu9250.getMres(); // Get magnetometer sensitivity |
sunninety1 | 3:4a1bc31c360f | 177 | // pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes); |
sunninety1 | 3:4a1bc31c360f | 178 | // pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes); |
sunninety1 | 3:4a1bc31c360f | 179 | // pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes); |
sunninety1 | 3:4a1bc31c360f | 180 | magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated |
sunninety1 | 3:4a1bc31c360f | 181 | magbias[1] = +120.; // User environmental x-axis correction in milliGauss |
sunninety1 | 3:4a1bc31c360f | 182 | magbias[2] = +125.; // User environmental x-axis correction in milliGauss |
sunninety1 | 3:4a1bc31c360f | 183 | |
sunninety1 | 2:01ca44dd3908 | 184 | while(1) { |
sunninety1 | 3:4a1bc31c360f | 185 | |
sunninety1 | 3:4a1bc31c360f | 186 | // If intPin goes high, all data registers have new data |
sunninety1 | 3:4a1bc31c360f | 187 | if(mpu9250.readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt |
sunninety1 | 3:4a1bc31c360f | 188 | |
sunninety1 | 3:4a1bc31c360f | 189 | mpu9250.readAccelData(accelCount); // Read the x/y/z adc values |
sunninety1 | 3:4a1bc31c360f | 190 | // Now we'll calculate the accleration value into actual g's |
sunninety1 | 3:4a1bc31c360f | 191 | ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set |
sunninety1 | 3:4a1bc31c360f | 192 | ay = (float)accelCount[1]*aRes - accelBias[1]; |
sunninety1 | 3:4a1bc31c360f | 193 | az = (float)accelCount[2]*aRes - accelBias[2]; |
sunninety1 | 3:4a1bc31c360f | 194 | |
sunninety1 | 3:4a1bc31c360f | 195 | mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values |
sunninety1 | 3:4a1bc31c360f | 196 | // Calculate the gyro value into actual degrees per second |
sunninety1 | 3:4a1bc31c360f | 197 | gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set |
sunninety1 | 3:4a1bc31c360f | 198 | gy = (float)gyroCount[1]*gRes - gyroBias[1]; |
sunninety1 | 3:4a1bc31c360f | 199 | gz = (float)gyroCount[2]*gRes - gyroBias[2]; |
sunninety1 | 3:4a1bc31c360f | 200 | |
sunninety1 | 3:4a1bc31c360f | 201 | mpu9250.readMagData(magCount); // Read the x/y/z adc values |
sunninety1 | 3:4a1bc31c360f | 202 | // Calculate the magnetometer values in milliGauss |
sunninety1 | 3:4a1bc31c360f | 203 | // Include factory calibration per data sheet and user environmental corrections |
sunninety1 | 3:4a1bc31c360f | 204 | mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set |
sunninety1 | 3:4a1bc31c360f | 205 | my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; |
sunninety1 | 3:4a1bc31c360f | 206 | mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; |
sunninety1 | 2:01ca44dd3908 | 207 | } |
sunninety1 | 3:4a1bc31c360f | 208 | |
sunninety1 | 3:4a1bc31c360f | 209 | Now = t.read_us(); |
sunninety1 | 3:4a1bc31c360f | 210 | deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update |
sunninety1 | 3:4a1bc31c360f | 211 | lastUpdate = Now; |
sunninety1 | 3:4a1bc31c360f | 212 | |
sunninety1 | 3:4a1bc31c360f | 213 | sum += deltat; |
sunninety1 | 3:4a1bc31c360f | 214 | sumCount++; |
sunninety1 | 3:4a1bc31c360f | 215 | |
sunninety1 | 3:4a1bc31c360f | 216 | // if(lastUpdate - firstUpdate > 10000000.0f) { |
sunninety1 | 3:4a1bc31c360f | 217 | // beta = 0.04; // decrease filter gain after stabilized |
sunninety1 | 3:4a1bc31c360f | 218 | // zeta = 0.015; // increasey bias drift gain after stabilized |
sunninety1 | 3:4a1bc31c360f | 219 | // } |
sunninety1 | 3:4a1bc31c360f | 220 | |
sunninety1 | 3:4a1bc31c360f | 221 | // Pass gyro rate as rad/s |
sunninety1 | 3:4a1bc31c360f | 222 | // mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); |
sunninety1 | 3:4a1bc31c360f | 223 | mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); |
sunninety1 | 3:4a1bc31c360f | 224 | |
sunninety1 | 3:4a1bc31c360f | 225 | // Serial print and/or display at 0.5 s rate independent of data rates |
sunninety1 | 3:4a1bc31c360f | 226 | delt_t = t.read_ms() - count; |
sunninety1 | 3:4a1bc31c360f | 227 | if (delt_t > 100) { // update LCD once per half-second independent of read rate |
sunninety1 | 3:4a1bc31c360f | 228 | |
sunninety1 | 4:7b04752df27f | 229 | /*pc.printf("ax = %f", 1000*ax); |
sunninety1 | 3:4a1bc31c360f | 230 | pc.printf(" ay = %f", 1000*ay); |
sunninety1 | 3:4a1bc31c360f | 231 | pc.printf(" az = %f mg\n\r", 1000*az); |
sunninety1 | 4:7b04752df27f | 232 | */ |
sunninety1 | 4:7b04752df27f | 233 | pc.printf("gx = %f", gx); |
sunninety1 | 4:7b04752df27f | 234 | pc.printf(" gy = %f", gy); |
sunninety1 | 4:7b04752df27f | 235 | pc.printf(" gz = %f deg/s\n\r", gz); |
sunninety1 | 3:4a1bc31c360f | 236 | |
sunninety1 | 3:4a1bc31c360f | 237 | // pc.printf("gx = %f", mx); |
sunninety1 | 3:4a1bc31c360f | 238 | // pc.printf(" gy = %f", my); |
sunninety1 | 3:4a1bc31c360f | 239 | // pc.printf(" gz = %f mG\n\r", mz); |
sunninety1 | 3:4a1bc31c360f | 240 | |
sunninety1 | 3:4a1bc31c360f | 241 | tempCount = mpu9250.readTempData(); // Read the adc values |
sunninety1 | 3:4a1bc31c360f | 242 | temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade |
sunninety1 | 3:4a1bc31c360f | 243 | // pc.printf(" temperature = %f C\n\r", temperature); |
sunninety1 | 3:4a1bc31c360f | 244 | // |
sunninety1 | 3:4a1bc31c360f | 245 | // pc.printf("q0 = %f\n\r", q[0]); |
sunninety1 | 3:4a1bc31c360f | 246 | // pc.printf("q1 = %f\n\r", q[1]); |
sunninety1 | 3:4a1bc31c360f | 247 | // pc.printf("q2 = %f\n\r", q[2]); |
sunninety1 | 3:4a1bc31c360f | 248 | // pc.printf("q3 = %f\n\r", q[3]); |
sunninety1 | 3:4a1bc31c360f | 249 | |
sunninety1 | 3:4a1bc31c360f | 250 | /* lcd.clear(); |
sunninety1 | 3:4a1bc31c360f | 251 | lcd.printString("MPU9250", 0, 0); |
sunninety1 | 3:4a1bc31c360f | 252 | lcd.printString("x y z", 0, 1); |
sunninety1 | 3:4a1bc31c360f | 253 | sprintf(buffer, "%d %d %d mg", (int)(1000.0f*ax), (int)(1000.0f*ay), (int)(1000.0f*az)); |
sunninety1 | 3:4a1bc31c360f | 254 | lcd.printString(buffer, 0, 2); |
sunninety1 | 3:4a1bc31c360f | 255 | sprintf(buffer, "%d %d %d deg/s", (int)gx, (int)gy, (int)gz); |
sunninety1 | 3:4a1bc31c360f | 256 | lcd.printString(buffer, 0, 3); |
sunninety1 | 3:4a1bc31c360f | 257 | sprintf(buffer, "%d %d %d mG", (int)mx, (int)my, (int)mz); |
sunninety1 | 3:4a1bc31c360f | 258 | lcd.printString(buffer, 0, 4); |
sunninety1 | 3:4a1bc31c360f | 259 | */ |
sunninety1 | 3:4a1bc31c360f | 260 | // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. |
sunninety1 | 3:4a1bc31c360f | 261 | // In this coordinate system, the positive z-axis is down toward Earth. |
sunninety1 | 3:4a1bc31c360f | 262 | // 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. |
sunninety1 | 3:4a1bc31c360f | 263 | // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. |
sunninety1 | 3:4a1bc31c360f | 264 | // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. |
sunninety1 | 3:4a1bc31c360f | 265 | // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. |
sunninety1 | 3:4a1bc31c360f | 266 | // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be |
sunninety1 | 3:4a1bc31c360f | 267 | // applied in the correct order which for this configuration is yaw, pitch, and then roll. |
sunninety1 | 3:4a1bc31c360f | 268 | // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. |
sunninety1 | 3:4a1bc31c360f | 269 | 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]); |
sunninety1 | 3:4a1bc31c360f | 270 | pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); |
sunninety1 | 3:4a1bc31c360f | 271 | 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]); |
sunninety1 | 3:4a1bc31c360f | 272 | pitch *= 180.0f / PI; |
sunninety1 | 3:4a1bc31c360f | 273 | yaw *= 180.0f / PI; |
sunninety1 | 3:4a1bc31c360f | 274 | yaw -= 85.0f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 |
sunninety1 | 3:4a1bc31c360f | 275 | roll *= 180.0f / PI; |
sunninety1 | 3:4a1bc31c360f | 276 | |
sunninety1 | 3:4a1bc31c360f | 277 | // pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll); |
sunninety1 | 3:4a1bc31c360f | 278 | // pc.printf("average rate = %f\n\r", (float) sumCount/sum); |
sunninety1 | 3:4a1bc31c360f | 279 | // sprintf(buffer, "YPR: %f %f %f", yaw, pitch, roll); |
sunninety1 | 3:4a1bc31c360f | 280 | // lcd.printString(buffer, 0, 4); |
sunninety1 | 3:4a1bc31c360f | 281 | // sprintf(buffer, "rate = %f", (float) sumCount/sum); |
sunninety1 | 3:4a1bc31c360f | 282 | // lcd.printString(buffer, 0, 5); |
sunninety1 | 3:4a1bc31c360f | 283 | |
sunninety1 | 3:4a1bc31c360f | 284 | |
sunninety1 | 3:4a1bc31c360f | 285 | acc_xyz[0]=ax; |
sunninety1 | 3:4a1bc31c360f | 286 | acc_xyz[1]=ay; |
sunninety1 | 3:4a1bc31c360f | 287 | acc_xyz[2]=az; |
sunninety1 | 3:4a1bc31c360f | 288 | float mag_a=sqrt(pow(acc_xyz[0],2)+pow(acc_xyz[1],2)+pow(acc_xyz[2],2)); |
sunninety1 | 3:4a1bc31c360f | 289 | AccelToVelocity(mag_a*cos(yaw),mag_a*sin(yaw),mag_a*sin(roll),float(delt_t)/10);//deltat*1000000 |
sunninety1 | 3:4a1bc31c360f | 290 | static float fillter_vx=0; |
sunninety1 | 3:4a1bc31c360f | 291 | static float fillter_vy=0; |
sunninety1 | 3:4a1bc31c360f | 292 | static float fillter_vz=0; |
sunninety1 | 3:4a1bc31c360f | 293 | fillter_vx=v_xyz[0]*0.5+fillter_vx*0.5; |
sunninety1 | 3:4a1bc31c360f | 294 | fillter_vy=v_xyz[1]*0.5+fillter_vy*0.5; |
sunninety1 | 3:4a1bc31c360f | 295 | fillter_vz=v_xyz[2]*0.5+fillter_vz*0.5; |
sunninety1 | 3:4a1bc31c360f | 296 | //VelocityToDisplacement(float(delt_t)); |
sunninety1 | 3:4a1bc31c360f | 297 | //pc.printf("%f\n",sqrt(displacement_body[0]*displacement_body[0])); |
sunninety1 | 3:4a1bc31c360f | 298 | //pc.printf("%f %f\n",displacement_body[0],displacement_body[1]); |
sunninety1 | 3:4a1bc31c360f | 299 | // displacement_world[0]+=sqrt(pow(displacement_body[0],2)+pow(displacement_body[1],2)+pow(displacement_body[2],2)) |
sunninety1 | 3:4a1bc31c360f | 300 | // pc.printf("%f %f \n",v_xyz[0],v_xyz[1]); |
sunninety1 | 3:4a1bc31c360f | 301 | // pc.printf("%f %f %f\n",fillter_vx,fillter_vy,fillter_vz); |
sunninety1 | 3:4a1bc31c360f | 302 | myled= !myled; |
sunninety1 | 3:4a1bc31c360f | 303 | count = t.read_ms(); |
sunninety1 | 3:4a1bc31c360f | 304 | if(count > 1<<21) { |
sunninety1 | 3:4a1bc31c360f | 305 | t.start(); // start the timer over again if ~30 minutes has passed |
sunninety1 | 3:4a1bc31c360f | 306 | count = 0; |
sunninety1 | 3:4a1bc31c360f | 307 | deltat= 0; |
sunninety1 | 3:4a1bc31c360f | 308 | lastUpdate = t.read_us(); |
sunninety1 | 3:4a1bc31c360f | 309 | } |
sunninety1 | 3:4a1bc31c360f | 310 | sum = 0; |
sunninety1 | 3:4a1bc31c360f | 311 | sumCount = 0; |
sunninety1 | 3:4a1bc31c360f | 312 | //----------------------------------------------------------------------------------------- |
sunninety1 | 3:4a1bc31c360f | 313 | |
sunninety1 | 2:01ca44dd3908 | 314 | if(serial.writeable()) { |
sunninety1 | 4:7b04752df27f | 315 | serial.printf("%f %f %f %f %f %f %f %f %f \n",ax,ay,az,gx,gy,gz,roll,pitch,yaw); |
sunninety1 | 4:7b04752df27f | 316 | //pc.printf("%f_%f_%f_g%f_g%f_g%f_ \n",ax,ay,az,gx,gy,gz); |
sunninety1 | 4:7b04752df27f | 317 | |
sunninety1 | 4:7b04752df27f | 318 | pc.printf("%f_%f_%f \n",roll,pitch,yaw); |
sunninety1 | 4:7b04752df27f | 319 | |
sunninety1 | 3:4a1bc31c360f | 320 | |
sunninety1 | 3:4a1bc31c360f | 321 | } |
sunninety1 | 3:4a1bc31c360f | 322 | } |
sunninety1 | 3:4a1bc31c360f | 323 | |
sunninety1 | 3:4a1bc31c360f | 324 | |
sunninety1 | 2:01ca44dd3908 | 325 | } |
sunninety1 | 3:4a1bc31c360f | 326 | |
sunninety1 | 2:01ca44dd3908 | 327 | } |
sunninety1 | 3:4a1bc31c360f | 328 |