interface imu mpu9250

Dependents:   AHRS_fillter

Committer:
soulx
Date:
Wed Jan 20 14:50:12 2016 +0000
Revision:
0:b502ea2d6ebb
crate lib imu interface

Who changed what in which revision?

UserRevisionLine numberNew contents of line
soulx 0:b502ea2d6ebb 1 #include "MPU9250.h"
soulx 0:b502ea2d6ebb 2
soulx 0:b502ea2d6ebb 3
soulx 0:b502ea2d6ebb 4 MPU9250::MPU9250(PinName sda, PinName scl, PinName tx, PinName rx, int address) : i2c(sda, scl), pc(tx,rx)
soulx 0:b502ea2d6ebb 5 {
soulx 0:b502ea2d6ebb 6 if(address == 0)
soulx 0:b502ea2d6ebb 7 MPU9250_ADDRESS = MPU9250_ADDRESS_68;
soulx 0:b502ea2d6ebb 8 else if(address == 1) MPU9250_ADDRESS = MPU9250_ADDRESS_69;
soulx 0:b502ea2d6ebb 9 else {
soulx 0:b502ea2d6ebb 10 printf("Wrong Address\n");
soulx 0:b502ea2d6ebb 11 while(1);
soulx 0:b502ea2d6ebb 12 }
soulx 0:b502ea2d6ebb 13
soulx 0:b502ea2d6ebb 14 i2c.frequency(400000);
soulx 0:b502ea2d6ebb 15
soulx 0:b502ea2d6ebb 16 for(int i=0; i<=3; i++) {
soulx 0:b502ea2d6ebb 17 magCalibration[i] = 0;
soulx 0:b502ea2d6ebb 18 magbias[i] = 0;
soulx 0:b502ea2d6ebb 19 gyroBias[i] = 0;
soulx 0:b502ea2d6ebb 20 accelBias[i] = 0;
soulx 0:b502ea2d6ebb 21 }
soulx 0:b502ea2d6ebb 22 Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
soulx 0:b502ea2d6ebb 23 }
soulx 0:b502ea2d6ebb 24
soulx 0:b502ea2d6ebb 25 void MPU9250::Start()
soulx 0:b502ea2d6ebb 26 {
soulx 0:b502ea2d6ebb 27 whoami = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250
soulx 0:b502ea2d6ebb 28 pc.printf("I AM 0x%x\n\r", whoami);
soulx 0:b502ea2d6ebb 29 pc.printf("I SHOULD BE 0x71\n\r");
soulx 0:b502ea2d6ebb 30
soulx 0:b502ea2d6ebb 31 if (whoami == 0x71) { // WHO_AM_I should always be 0x68
soulx 0:b502ea2d6ebb 32 pc.printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami);
soulx 0:b502ea2d6ebb 33 pc.printf("MPU9250 is online...\n\r");
soulx 0:b502ea2d6ebb 34 wait(1);
soulx 0:b502ea2d6ebb 35
soulx 0:b502ea2d6ebb 36 resetMPU9250(); // Reset registers to default in preparation for device calibration
soulx 0:b502ea2d6ebb 37 MPU9250SelfTest(); // Start by performing self test and reporting values
soulx 0:b502ea2d6ebb 38 /*pc.printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]);
soulx 0:b502ea2d6ebb 39 pc.printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]);
soulx 0:b502ea2d6ebb 40 pc.printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]);
soulx 0:b502ea2d6ebb 41 pc.printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]);
soulx 0:b502ea2d6ebb 42 pc.printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]);
soulx 0:b502ea2d6ebb 43 pc.printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]);*/
soulx 0:b502ea2d6ebb 44 calibrateMPU9250(); // Calibrate gyro and accelerometers, load biases in bias registers
soulx 0:b502ea2d6ebb 45 /*pc.printf("x gyro bias = %f\n\r", gyroBias[0]);
soulx 0:b502ea2d6ebb 46 pc.printf("y gyro bias = %f\n\r", gyroBias[1]);
soulx 0:b502ea2d6ebb 47 pc.printf("z gyro bias = %f\n\r", gyroBias[2]);
soulx 0:b502ea2d6ebb 48 pc.printf("x accel bias = %f\n\r", accelBias[0]);
soulx 0:b502ea2d6ebb 49 pc.printf("y accel bias = %f\n\r", accelBias[1]);
soulx 0:b502ea2d6ebb 50 pc.printf("z accel bias = %f\n\r", accelBias[2]);*/
soulx 0:b502ea2d6ebb 51 wait(2);
soulx 0:b502ea2d6ebb 52 initMPU9250();
soulx 0:b502ea2d6ebb 53 pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
soulx 0:b502ea2d6ebb 54 initAK8963();
soulx 0:b502ea2d6ebb 55 pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer
soulx 0:b502ea2d6ebb 56
soulx 0:b502ea2d6ebb 57 whoami = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for MPU-9250
soulx 0:b502ea2d6ebb 58 pc.printf("I AM 0x%x\n\r", whoami);
soulx 0:b502ea2d6ebb 59 pc.printf("I SHOULD BE 0x48\n\r");
soulx 0:b502ea2d6ebb 60 if(whoami != 0x48) {
soulx 0:b502ea2d6ebb 61 while(1);
soulx 0:b502ea2d6ebb 62 }
soulx 0:b502ea2d6ebb 63 /*pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale));
soulx 0:b502ea2d6ebb 64 pc.printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale));
soulx 0:b502ea2d6ebb 65 if(Mscale == 0) pc.printf("Magnetometer resolution = 14 bits\n\r");
soulx 0:b502ea2d6ebb 66 if(Mscale == 1) pc.printf("Magnetometer resolution = 16 bits\n\r");
soulx 0:b502ea2d6ebb 67 if(Mmode == 2) pc.printf("Magnetometer ODR = 8 Hz\n\r");
soulx 0:b502ea2d6ebb 68 if(Mmode == 6) pc.printf("Magnetometer ODR = 100 Hz\n\r");*/
soulx 0:b502ea2d6ebb 69 wait(1);
soulx 0:b502ea2d6ebb 70 } else {
soulx 0:b502ea2d6ebb 71 pc.printf("Could not connect to MPU9250: \n\r");
soulx 0:b502ea2d6ebb 72 pc.printf("%#x \n", whoami);
soulx 0:b502ea2d6ebb 73
soulx 0:b502ea2d6ebb 74 while(1) ; // Loop forever if communication doesn't happen
soulx 0:b502ea2d6ebb 75 }
soulx 0:b502ea2d6ebb 76
soulx 0:b502ea2d6ebb 77
soulx 0:b502ea2d6ebb 78 getAres(); // Get accelerometer sensitivity
soulx 0:b502ea2d6ebb 79 getGres(); // Get gyro sensitivity
soulx 0:b502ea2d6ebb 80 getMres(); // Get magnetometer sensitivity
soulx 0:b502ea2d6ebb 81 /*pc.printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes);
soulx 0:b502ea2d6ebb 82 pc.printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes);
soulx 0:b502ea2d6ebb 83 pc.printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes);*/
soulx 0:b502ea2d6ebb 84
soulx 0:b502ea2d6ebb 85 MagCal();
soulx 0:b502ea2d6ebb 86 }
soulx 0:b502ea2d6ebb 87
soulx 0:b502ea2d6ebb 88 void MPU9250::ReadRawAccGyroMag()
soulx 0:b502ea2d6ebb 89 {
soulx 0:b502ea2d6ebb 90 // If intPin goes high, all data registers have new data
soulx 0:b502ea2d6ebb 91 if(readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt
soulx 0:b502ea2d6ebb 92
soulx 0:b502ea2d6ebb 93 readAccelData(); // Read the x/y/z adc values
soulx 0:b502ea2d6ebb 94 AccelXYZCal();
soulx 0:b502ea2d6ebb 95 // Now we'll calculate the accleration value into actual g's
soulx 0:b502ea2d6ebb 96 /*ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
soulx 0:b502ea2d6ebb 97 ay = (float)accelCount[1]*aRes - accelBias[1];
soulx 0:b502ea2d6ebb 98 az = (float)accelCount[2]*aRes - accelBias[2];*/
soulx 0:b502ea2d6ebb 99
soulx 0:b502ea2d6ebb 100 readGyroData(); // Read the x/y/z adc values
soulx 0:b502ea2d6ebb 101 GyroXYZCal();
soulx 0:b502ea2d6ebb 102 // Calculate the gyro value into actual degrees per second
soulx 0:b502ea2d6ebb 103 /*gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
soulx 0:b502ea2d6ebb 104 gy = (float)gyroCount[1]*gRes - gyroBias[1];
soulx 0:b502ea2d6ebb 105 gz = (float)gyroCount[2]*gRes - gyroBias[2];*/
soulx 0:b502ea2d6ebb 106
soulx 0:b502ea2d6ebb 107 readMagData(); // Read the x/y/z adc values
soulx 0:b502ea2d6ebb 108 MagXYZCal();
soulx 0:b502ea2d6ebb 109 /*mx = ((float)magCount[0]-xmin)*magCalibration[0] + magbias[0]; // get actual magnetometer value, this depends on scale being set
soulx 0:b502ea2d6ebb 110 my = ((float)magCount[1]-ymin)*magCalibration[1] + magbias[1];
soulx 0:b502ea2d6ebb 111 mz = ((float)magCount[2]-zmin)*magCalibration[2] + magbias[2];*/
soulx 0:b502ea2d6ebb 112 }
soulx 0:b502ea2d6ebb 113 }
soulx 0:b502ea2d6ebb 114
soulx 0:b502ea2d6ebb 115 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
soulx 0:b502ea2d6ebb 116 {
soulx 0:b502ea2d6ebb 117 char data_write[2];
soulx 0:b502ea2d6ebb 118 data_write[0] = subAddress;
soulx 0:b502ea2d6ebb 119 data_write[1] = data;
soulx 0:b502ea2d6ebb 120 i2c.write(address, data_write, 2, 0);
soulx 0:b502ea2d6ebb 121 }
soulx 0:b502ea2d6ebb 122
soulx 0:b502ea2d6ebb 123 char MPU9250::readByte(uint8_t address, uint8_t subAddress)
soulx 0:b502ea2d6ebb 124 {
soulx 0:b502ea2d6ebb 125 char data[1]; // `data` will store the register data
soulx 0:b502ea2d6ebb 126 char data_write[1];
soulx 0:b502ea2d6ebb 127 data_write[0] = subAddress;
soulx 0:b502ea2d6ebb 128 i2c.write(address, data_write, 1, 1); // no stop
soulx 0:b502ea2d6ebb 129 i2c.read(address, data, 1, 0);
soulx 0:b502ea2d6ebb 130 return data[0];
soulx 0:b502ea2d6ebb 131 }
soulx 0:b502ea2d6ebb 132
soulx 0:b502ea2d6ebb 133 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
soulx 0:b502ea2d6ebb 134 {
soulx 0:b502ea2d6ebb 135 char data[14];
soulx 0:b502ea2d6ebb 136 char data_write[1];
soulx 0:b502ea2d6ebb 137 data_write[0] = subAddress;
soulx 0:b502ea2d6ebb 138 i2c.write(address, data_write, 1, 1); // no stop
soulx 0:b502ea2d6ebb 139 i2c.read(address, data, count, 0);
soulx 0:b502ea2d6ebb 140 for(int ii = 0; ii < count; ii++) {
soulx 0:b502ea2d6ebb 141 dest[ii] = data[ii];
soulx 0:b502ea2d6ebb 142 }
soulx 0:b502ea2d6ebb 143 }
soulx 0:b502ea2d6ebb 144
soulx 0:b502ea2d6ebb 145
soulx 0:b502ea2d6ebb 146 void MPU9250::setMres()
soulx 0:b502ea2d6ebb 147 {
soulx 0:b502ea2d6ebb 148 getMres();
soulx 0:b502ea2d6ebb 149 switch (Mscale) {
soulx 0:b502ea2d6ebb 150 // Possible magnetometer scales (and their register bit settings) are:
soulx 0:b502ea2d6ebb 151 // 14 bit resolution (0) and 16 bit resolution (1)
soulx 0:b502ea2d6ebb 152 case MFS_14BITS:
soulx 0:b502ea2d6ebb 153 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
soulx 0:b502ea2d6ebb 154 break;
soulx 0:b502ea2d6ebb 155 case MFS_16BITS:
soulx 0:b502ea2d6ebb 156 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
soulx 0:b502ea2d6ebb 157 break;
soulx 0:b502ea2d6ebb 158 }
soulx 0:b502ea2d6ebb 159 }
soulx 0:b502ea2d6ebb 160
soulx 0:b502ea2d6ebb 161
soulx 0:b502ea2d6ebb 162 void MPU9250::setGres()
soulx 0:b502ea2d6ebb 163 {
soulx 0:b502ea2d6ebb 164 getGres();
soulx 0:b502ea2d6ebb 165 switch (Gscale) {
soulx 0:b502ea2d6ebb 166 // Possible gyro scales (and their register bit settings) are:
soulx 0:b502ea2d6ebb 167 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
soulx 0:b502ea2d6ebb 168 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
soulx 0:b502ea2d6ebb 169 case GFS_250DPS:
soulx 0:b502ea2d6ebb 170 gRes = 250.0/32768.0;
soulx 0:b502ea2d6ebb 171 break;
soulx 0:b502ea2d6ebb 172 case GFS_500DPS:
soulx 0:b502ea2d6ebb 173 gRes = 500.0/32768.0;
soulx 0:b502ea2d6ebb 174 break;
soulx 0:b502ea2d6ebb 175 case GFS_1000DPS:
soulx 0:b502ea2d6ebb 176 gRes = 1000.0/32768.0;
soulx 0:b502ea2d6ebb 177 break;
soulx 0:b502ea2d6ebb 178 case GFS_2000DPS:
soulx 0:b502ea2d6ebb 179 gRes = 2000.0/32768.0;
soulx 0:b502ea2d6ebb 180 break;
soulx 0:b502ea2d6ebb 181 }
soulx 0:b502ea2d6ebb 182 }
soulx 0:b502ea2d6ebb 183
soulx 0:b502ea2d6ebb 184 void MPU9250::setAres()
soulx 0:b502ea2d6ebb 185 {
soulx 0:b502ea2d6ebb 186 getAres();
soulx 0:b502ea2d6ebb 187 switch (Ascale) {
soulx 0:b502ea2d6ebb 188 // Possible accelerometer scales (and their register bit settings) are:
soulx 0:b502ea2d6ebb 189 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
soulx 0:b502ea2d6ebb 190 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
soulx 0:b502ea2d6ebb 191 case AFS_2G:
soulx 0:b502ea2d6ebb 192 aRes = 2.0/32768.0;
soulx 0:b502ea2d6ebb 193 break;
soulx 0:b502ea2d6ebb 194 case AFS_4G:
soulx 0:b502ea2d6ebb 195 aRes = 4.0/32768.0;
soulx 0:b502ea2d6ebb 196 break;
soulx 0:b502ea2d6ebb 197 case AFS_8G:
soulx 0:b502ea2d6ebb 198 aRes = 8.0/32768.0;
soulx 0:b502ea2d6ebb 199 break;
soulx 0:b502ea2d6ebb 200 case AFS_16G:
soulx 0:b502ea2d6ebb 201 aRes = 16.0/32768.0;
soulx 0:b502ea2d6ebb 202 break;
soulx 0:b502ea2d6ebb 203 }
soulx 0:b502ea2d6ebb 204 }
soulx 0:b502ea2d6ebb 205
soulx 0:b502ea2d6ebb 206 void MPU9250::getMres()
soulx 0:b502ea2d6ebb 207 {
soulx 0:b502ea2d6ebb 208 Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
soulx 0:b502ea2d6ebb 209 }
soulx 0:b502ea2d6ebb 210
soulx 0:b502ea2d6ebb 211
soulx 0:b502ea2d6ebb 212 void MPU9250::getGres()
soulx 0:b502ea2d6ebb 213 {
soulx 0:b502ea2d6ebb 214 Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
soulx 0:b502ea2d6ebb 215 }
soulx 0:b502ea2d6ebb 216
soulx 0:b502ea2d6ebb 217 void MPU9250::getAres()
soulx 0:b502ea2d6ebb 218 {
soulx 0:b502ea2d6ebb 219 Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G
soulx 0:b502ea2d6ebb 220 }
soulx 0:b502ea2d6ebb 221
soulx 0:b502ea2d6ebb 222 void MPU9250::MagCal()
soulx 0:b502ea2d6ebb 223 {
soulx 0:b502ea2d6ebb 224 printf("START scan mag\n\r\n\r\n\r");
soulx 0:b502ea2d6ebb 225
soulx 0:b502ea2d6ebb 226 //Assign random value before calibrate
soulx 0:b502ea2d6ebb 227 /*xmax = -4914.0f;
soulx 0:b502ea2d6ebb 228 xmin = 4914.0f;
soulx 0:b502ea2d6ebb 229
soulx 0:b502ea2d6ebb 230 ymax = -4914.0;
soulx 0:b502ea2d6ebb 231 ymin = 4914.0f;
soulx 0:b502ea2d6ebb 232
soulx 0:b502ea2d6ebb 233 zmax = -4914.0;
soulx 0:b502ea2d6ebb 234 zmin = 4914.0f;
soulx 0:b502ea2d6ebb 235
soulx 0:b502ea2d6ebb 236 change=false;
soulx 0:b502ea2d6ebb 237
soulx 0:b502ea2d6ebb 238 while(1) {
soulx 0:b502ea2d6ebb 239 readMagData(magCount);
soulx 0:b502ea2d6ebb 240
soulx 0:b502ea2d6ebb 241 if(magCount[0]<xmin) {
soulx 0:b502ea2d6ebb 242 xmin = magCount[0];
soulx 0:b502ea2d6ebb 243 change = true;
soulx 0:b502ea2d6ebb 244 }
soulx 0:b502ea2d6ebb 245 if(magCount[0]>xmax) {
soulx 0:b502ea2d6ebb 246 xmax = magCount[0];
soulx 0:b502ea2d6ebb 247 change = true;
soulx 0:b502ea2d6ebb 248 }
soulx 0:b502ea2d6ebb 249
soulx 0:b502ea2d6ebb 250 if(magCount[1]<ymin) {
soulx 0:b502ea2d6ebb 251 ymin = magCount[1];
soulx 0:b502ea2d6ebb 252 change = true;
soulx 0:b502ea2d6ebb 253 }
soulx 0:b502ea2d6ebb 254 if(magCount[1]>ymax) {
soulx 0:b502ea2d6ebb 255 ymax = magCount[1];
soulx 0:b502ea2d6ebb 256 change = true;
soulx 0:b502ea2d6ebb 257 }
soulx 0:b502ea2d6ebb 258
soulx 0:b502ea2d6ebb 259
soulx 0:b502ea2d6ebb 260 if(magCount[2]<zmin) {
soulx 0:b502ea2d6ebb 261 zmin = magCount[2];
soulx 0:b502ea2d6ebb 262 change = true;
soulx 0:b502ea2d6ebb 263 }
soulx 0:b502ea2d6ebb 264 if(magCount[2]>zmax) {
soulx 0:b502ea2d6ebb 265 zmax = magCount[2];
soulx 0:b502ea2d6ebb 266 change = true;
soulx 0:b502ea2d6ebb 267 }
soulx 0:b502ea2d6ebb 268
soulx 0:b502ea2d6ebb 269 if(change==true) {
soulx 0:b502ea2d6ebb 270 printf("Mx Max= %f Min= %f\n\r",xmax,xmin);
soulx 0:b502ea2d6ebb 271 printf("My Max= %f Min= %f\n\r",ymax,ymin);
soulx 0:b502ea2d6ebb 272 printf("Mz Max= %f Min= %f\n\r",zmax,zmin);
soulx 0:b502ea2d6ebb 273 change=false;
soulx 0:b502ea2d6ebb 274 }*/
soulx 0:b502ea2d6ebb 275
soulx 0:b502ea2d6ebb 276 //Out of Calibration loop
soulx 0:b502ea2d6ebb 277 /*if(button==1) {
soulx 0:b502ea2d6ebb 278 while(button==1);
soulx 0:b502ea2d6ebb 279 break;
soulx 0:b502ea2d6ebb 280 }*/
soulx 0:b502ea2d6ebb 281 //}
soulx 0:b502ea2d6ebb 282
soulx 0:b502ea2d6ebb 283
soulx 0:b502ea2d6ebb 284 xmax = 188.000000;
soulx 0:b502ea2d6ebb 285 xmin = -316.000000;
soulx 0:b502ea2d6ebb 286 ymax = 485.000000;
soulx 0:b502ea2d6ebb 287 ymin = -26.000000;
soulx 0:b502ea2d6ebb 288 zmax = 165.000000;
soulx 0:b502ea2d6ebb 289 xmin = -230.000000;
soulx 0:b502ea2d6ebb 290
soulx 0:b502ea2d6ebb 291 magbias[0] = -1.0;
soulx 0:b502ea2d6ebb 292 magbias[1] = -1.0;
soulx 0:b502ea2d6ebb 293 magbias[2] = -1.0;
soulx 0:b502ea2d6ebb 294
soulx 0:b502ea2d6ebb 295 magCalibration[0] = 2.0f / (xmax -xmin);
soulx 0:b502ea2d6ebb 296 magCalibration[1] = 2.0f / (ymax -ymin);
soulx 0:b502ea2d6ebb 297 magCalibration[2] = 2.0f / (zmax -zmin);
soulx 0:b502ea2d6ebb 298
soulx 0:b502ea2d6ebb 299 printf("mag[0] %f",magbias[0]);
soulx 0:b502ea2d6ebb 300 printf("mag[1] %f",magbias[1]);
soulx 0:b502ea2d6ebb 301 printf("mag[2] %f\n\r",magbias[2]);
soulx 0:b502ea2d6ebb 302 }
soulx 0:b502ea2d6ebb 303
soulx 0:b502ea2d6ebb 304 void MPU9250::AccelXYZCal()
soulx 0:b502ea2d6ebb 305 {
soulx 0:b502ea2d6ebb 306 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set
soulx 0:b502ea2d6ebb 307 ay = (float)accelCount[1]*aRes - accelBias[1];
soulx 0:b502ea2d6ebb 308 az = (float)accelCount[2]*aRes - accelBias[2];
soulx 0:b502ea2d6ebb 309 }
soulx 0:b502ea2d6ebb 310
soulx 0:b502ea2d6ebb 311 void MPU9250::GyroXYZCal()
soulx 0:b502ea2d6ebb 312 {
soulx 0:b502ea2d6ebb 313 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set
soulx 0:b502ea2d6ebb 314 gy = (float)gyroCount[1]*gRes - gyroBias[1];
soulx 0:b502ea2d6ebb 315 gz = (float)gyroCount[2]*gRes - gyroBias[2];
soulx 0:b502ea2d6ebb 316 }
soulx 0:b502ea2d6ebb 317
soulx 0:b502ea2d6ebb 318 void MPU9250::MagXYZCal()
soulx 0:b502ea2d6ebb 319 {
soulx 0:b502ea2d6ebb 320 mx = ((float)magCount[0]-xmin)*magCalibration[0] + magbias[0]; // get actual magnetometer value, this depends on scale being set
soulx 0:b502ea2d6ebb 321 my = ((float)magCount[1]-ymin)*magCalibration[1] + magbias[1];
soulx 0:b502ea2d6ebb 322 mz = ((float)magCount[2]-zmin)*magCalibration[2] + magbias[2];
soulx 0:b502ea2d6ebb 323 }
soulx 0:b502ea2d6ebb 324
soulx 0:b502ea2d6ebb 325
soulx 0:b502ea2d6ebb 326 void MPU9250::readAccelData()
soulx 0:b502ea2d6ebb 327 {
soulx 0:b502ea2d6ebb 328 float destination[3] = {0,0,0};
soulx 0:b502ea2d6ebb 329 uint8_t rawData[6]; // x/y/z accel register data stored here
soulx 0:b502ea2d6ebb 330 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
soulx 0:b502ea2d6ebb 331 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 332 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 333 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 334
soulx 0:b502ea2d6ebb 335 for(int i=0; i<=2; i++)
soulx 0:b502ea2d6ebb 336 accelCount[i] = (float)destination[i];
soulx 0:b502ea2d6ebb 337 }
soulx 0:b502ea2d6ebb 338
soulx 0:b502ea2d6ebb 339 void MPU9250::readGyroData()
soulx 0:b502ea2d6ebb 340 {
soulx 0:b502ea2d6ebb 341 float destination[3] = {0,0,0};
soulx 0:b502ea2d6ebb 342 uint8_t rawData[6]; // x/y/z gyro register data stored here
soulx 0:b502ea2d6ebb 343 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
soulx 0:b502ea2d6ebb 344 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 345 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 346 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 347
soulx 0:b502ea2d6ebb 348 for(int i=0; i<=2; i++)
soulx 0:b502ea2d6ebb 349 gyroCount[i] = (float)destination[i];
soulx 0:b502ea2d6ebb 350 }
soulx 0:b502ea2d6ebb 351
soulx 0:b502ea2d6ebb 352 void MPU9250::readMagData()
soulx 0:b502ea2d6ebb 353 {
soulx 0:b502ea2d6ebb 354 float destination[3] = {0,0,0};
soulx 0:b502ea2d6ebb 355 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
soulx 0:b502ea2d6ebb 356 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
soulx 0:b502ea2d6ebb 357 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array
soulx 0:b502ea2d6ebb 358 uint8_t c = rawData[6]; // End data read by reading ST2 register
soulx 0:b502ea2d6ebb 359 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
soulx 0:b502ea2d6ebb 360 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 361 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian
soulx 0:b502ea2d6ebb 362 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
soulx 0:b502ea2d6ebb 363 }
soulx 0:b502ea2d6ebb 364 }
soulx 0:b502ea2d6ebb 365
soulx 0:b502ea2d6ebb 366 for(int i=0; i<=2; i++)
soulx 0:b502ea2d6ebb 367 magCount[i] = (float)destination[i];
soulx 0:b502ea2d6ebb 368 }
soulx 0:b502ea2d6ebb 369
soulx 0:b502ea2d6ebb 370 void MPU9250::readTempData()
soulx 0:b502ea2d6ebb 371 {
soulx 0:b502ea2d6ebb 372 int16_t destination;
soulx 0:b502ea2d6ebb 373 uint8_t rawData[2]; // x/y/z gyro register data stored here
soulx 0:b502ea2d6ebb 374 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
soulx 0:b502ea2d6ebb 375 destination = (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value
soulx 0:b502ea2d6ebb 376 destination = ((float) destination) / 333.87f + 21.0f;
soulx 0:b502ea2d6ebb 377 temperature = destination;
soulx 0:b502ea2d6ebb 378 }
soulx 0:b502ea2d6ebb 379
soulx 0:b502ea2d6ebb 380
soulx 0:b502ea2d6ebb 381 void MPU9250::resetMPU9250()
soulx 0:b502ea2d6ebb 382 {
soulx 0:b502ea2d6ebb 383 // reset device
soulx 0:b502ea2d6ebb 384 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
soulx 0:b502ea2d6ebb 385 wait(0.1);
soulx 0:b502ea2d6ebb 386 }
soulx 0:b502ea2d6ebb 387
soulx 0:b502ea2d6ebb 388 void MPU9250::initAK8963()
soulx 0:b502ea2d6ebb 389 {
soulx 0:b502ea2d6ebb 390 float destination[3] = {0,0,0};
soulx 0:b502ea2d6ebb 391 // First extract the factory calibration for each magnetometer axis
soulx 0:b502ea2d6ebb 392 uint8_t rawData[3]; // x/y/z gyro calibration data stored here
soulx 0:b502ea2d6ebb 393 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
soulx 0:b502ea2d6ebb 394 wait(0.01);
soulx 0:b502ea2d6ebb 395 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
soulx 0:b502ea2d6ebb 396 wait(0.01);
soulx 0:b502ea2d6ebb 397 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
soulx 0:b502ea2d6ebb 398 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc.
soulx 0:b502ea2d6ebb 399 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
soulx 0:b502ea2d6ebb 400 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
soulx 0:b502ea2d6ebb 401 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
soulx 0:b502ea2d6ebb 402 wait(0.01);
soulx 0:b502ea2d6ebb 403 // Configure the magnetometer for continuous read and highest resolution
soulx 0:b502ea2d6ebb 404 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
soulx 0:b502ea2d6ebb 405 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
soulx 0:b502ea2d6ebb 406 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
soulx 0:b502ea2d6ebb 407 wait(0.01);
soulx 0:b502ea2d6ebb 408
soulx 0:b502ea2d6ebb 409 for(int i=0; i<=2; i++)
soulx 0:b502ea2d6ebb 410 magCalibration[i] = destination[i];
soulx 0:b502ea2d6ebb 411 }
soulx 0:b502ea2d6ebb 412
soulx 0:b502ea2d6ebb 413
soulx 0:b502ea2d6ebb 414 void MPU9250::initMPU9250()
soulx 0:b502ea2d6ebb 415 {
soulx 0:b502ea2d6ebb 416 // Initialize MPU9250 device
soulx 0:b502ea2d6ebb 417 // wake up device
soulx 0:b502ea2d6ebb 418 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
soulx 0:b502ea2d6ebb 419 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
soulx 0:b502ea2d6ebb 420
soulx 0:b502ea2d6ebb 421 // get stable time source
soulx 0:b502ea2d6ebb 422 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
soulx 0:b502ea2d6ebb 423
soulx 0:b502ea2d6ebb 424 // Configure Gyro and Accelerometer
soulx 0:b502ea2d6ebb 425 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
soulx 0:b502ea2d6ebb 426 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
soulx 0:b502ea2d6ebb 427 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
soulx 0:b502ea2d6ebb 428 writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
soulx 0:b502ea2d6ebb 429
soulx 0:b502ea2d6ebb 430 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
soulx 0:b502ea2d6ebb 431 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
soulx 0:b502ea2d6ebb 432
soulx 0:b502ea2d6ebb 433 // Set gyroscope full scale range
soulx 0:b502ea2d6ebb 434 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
soulx 0:b502ea2d6ebb 435 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG);
soulx 0:b502ea2d6ebb 436 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
soulx 0:b502ea2d6ebb 437 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
soulx 0:b502ea2d6ebb 438 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
soulx 0:b502ea2d6ebb 439
soulx 0:b502ea2d6ebb 440 // Set accelerometer configuration
soulx 0:b502ea2d6ebb 441 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG);
soulx 0:b502ea2d6ebb 442 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
soulx 0:b502ea2d6ebb 443 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
soulx 0:b502ea2d6ebb 444 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer
soulx 0:b502ea2d6ebb 445
soulx 0:b502ea2d6ebb 446 // Set accelerometer sample rate configuration
soulx 0:b502ea2d6ebb 447 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
soulx 0:b502ea2d6ebb 448 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
soulx 0:b502ea2d6ebb 449 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2);
soulx 0:b502ea2d6ebb 450 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
soulx 0:b502ea2d6ebb 451 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
soulx 0:b502ea2d6ebb 452
soulx 0:b502ea2d6ebb 453 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
soulx 0:b502ea2d6ebb 454 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
soulx 0:b502ea2d6ebb 455
soulx 0:b502ea2d6ebb 456 // Configure Interrupts and Bypass Enable
soulx 0:b502ea2d6ebb 457 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
soulx 0:b502ea2d6ebb 458 // can join the I2C bus and all can be controlled by the Arduino as master
soulx 0:b502ea2d6ebb 459 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
soulx 0:b502ea2d6ebb 460 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
soulx 0:b502ea2d6ebb 461 }
soulx 0:b502ea2d6ebb 462
soulx 0:b502ea2d6ebb 463 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
soulx 0:b502ea2d6ebb 464 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
soulx 0:b502ea2d6ebb 465 void MPU9250::calibrateMPU9250()
soulx 0:b502ea2d6ebb 466 {
soulx 0:b502ea2d6ebb 467 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
soulx 0:b502ea2d6ebb 468 uint16_t ii, packet_count, fifo_count;
soulx 0:b502ea2d6ebb 469 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
soulx 0:b502ea2d6ebb 470
soulx 0:b502ea2d6ebb 471 // reset device, reset all registers, clear gyro and accelerometer bias registers
soulx 0:b502ea2d6ebb 472 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
soulx 0:b502ea2d6ebb 473 wait(0.1);
soulx 0:b502ea2d6ebb 474
soulx 0:b502ea2d6ebb 475 // get stable time source
soulx 0:b502ea2d6ebb 476 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
soulx 0:b502ea2d6ebb 477 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
soulx 0:b502ea2d6ebb 478 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
soulx 0:b502ea2d6ebb 479 wait(0.2);
soulx 0:b502ea2d6ebb 480
soulx 0:b502ea2d6ebb 481 // Configure device for bias calculation
soulx 0:b502ea2d6ebb 482 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
soulx 0:b502ea2d6ebb 483 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
soulx 0:b502ea2d6ebb 484 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
soulx 0:b502ea2d6ebb 485 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
soulx 0:b502ea2d6ebb 486 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
soulx 0:b502ea2d6ebb 487 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
soulx 0:b502ea2d6ebb 488 wait(0.015);
soulx 0:b502ea2d6ebb 489
soulx 0:b502ea2d6ebb 490 // Configure MPU9250 gyro and accelerometer for bias calculation
soulx 0:b502ea2d6ebb 491 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
soulx 0:b502ea2d6ebb 492 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
soulx 0:b502ea2d6ebb 493 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
soulx 0:b502ea2d6ebb 494 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
soulx 0:b502ea2d6ebb 495
soulx 0:b502ea2d6ebb 496 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
soulx 0:b502ea2d6ebb 497 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
soulx 0:b502ea2d6ebb 498
soulx 0:b502ea2d6ebb 499 // Configure FIFO to capture accelerometer and gyro data for bias calculation
soulx 0:b502ea2d6ebb 500 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
soulx 0:b502ea2d6ebb 501 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
soulx 0:b502ea2d6ebb 502 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
soulx 0:b502ea2d6ebb 503
soulx 0:b502ea2d6ebb 504 // At end of sample accumulation, turn off FIFO sensor read
soulx 0:b502ea2d6ebb 505 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
soulx 0:b502ea2d6ebb 506 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
soulx 0:b502ea2d6ebb 507 fifo_count = ((uint16_t)data[0] << 8) | data[1];
soulx 0:b502ea2d6ebb 508 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
soulx 0:b502ea2d6ebb 509
soulx 0:b502ea2d6ebb 510 for (ii = 0; ii < packet_count; ii++) {
soulx 0:b502ea2d6ebb 511 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
soulx 0:b502ea2d6ebb 512 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
soulx 0:b502ea2d6ebb 513 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
soulx 0:b502ea2d6ebb 514 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
soulx 0:b502ea2d6ebb 515 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
soulx 0:b502ea2d6ebb 516 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
soulx 0:b502ea2d6ebb 517 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
soulx 0:b502ea2d6ebb 518 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
soulx 0:b502ea2d6ebb 519
soulx 0:b502ea2d6ebb 520 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
soulx 0:b502ea2d6ebb 521 accel_bias[1] += (int32_t) accel_temp[1];
soulx 0:b502ea2d6ebb 522 accel_bias[2] += (int32_t) accel_temp[2];
soulx 0:b502ea2d6ebb 523 gyro_bias[0] += (int32_t) gyro_temp[0];
soulx 0:b502ea2d6ebb 524 gyro_bias[1] += (int32_t) gyro_temp[1];
soulx 0:b502ea2d6ebb 525 gyro_bias[2] += (int32_t) gyro_temp[2];
soulx 0:b502ea2d6ebb 526
soulx 0:b502ea2d6ebb 527 }
soulx 0:b502ea2d6ebb 528 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
soulx 0:b502ea2d6ebb 529 accel_bias[1] /= (int32_t) packet_count;
soulx 0:b502ea2d6ebb 530 accel_bias[2] /= (int32_t) packet_count;
soulx 0:b502ea2d6ebb 531 gyro_bias[0] /= (int32_t) packet_count;
soulx 0:b502ea2d6ebb 532 gyro_bias[1] /= (int32_t) packet_count;
soulx 0:b502ea2d6ebb 533 gyro_bias[2] /= (int32_t) packet_count;
soulx 0:b502ea2d6ebb 534
soulx 0:b502ea2d6ebb 535 if(accel_bias[2] > 0L) {
soulx 0:b502ea2d6ebb 536 accel_bias[2] -= (int32_t) accelsensitivity; // Remove gravity from the z-axis accelerometer bias calculation
soulx 0:b502ea2d6ebb 537 } else {
soulx 0:b502ea2d6ebb 538 accel_bias[2] += (int32_t) accelsensitivity;
soulx 0:b502ea2d6ebb 539 }
soulx 0:b502ea2d6ebb 540
soulx 0:b502ea2d6ebb 541 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
soulx 0:b502ea2d6ebb 542 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
soulx 0:b502ea2d6ebb 543 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
soulx 0:b502ea2d6ebb 544 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
soulx 0:b502ea2d6ebb 545 data[3] = (-gyro_bias[1]/4) & 0xFF;
soulx 0:b502ea2d6ebb 546 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
soulx 0:b502ea2d6ebb 547 data[5] = (-gyro_bias[2]/4) & 0xFF;
soulx 0:b502ea2d6ebb 548
soulx 0:b502ea2d6ebb 549 /// Push gyro biases to hardware registers
soulx 0:b502ea2d6ebb 550 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
soulx 0:b502ea2d6ebb 551 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
soulx 0:b502ea2d6ebb 552 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
soulx 0:b502ea2d6ebb 553 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
soulx 0:b502ea2d6ebb 554 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
soulx 0:b502ea2d6ebb 555 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
soulx 0:b502ea2d6ebb 556 */
soulx 0:b502ea2d6ebb 557 gyroBias[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
soulx 0:b502ea2d6ebb 558 gyroBias[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
soulx 0:b502ea2d6ebb 559 gyroBias[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
soulx 0:b502ea2d6ebb 560
soulx 0:b502ea2d6ebb 561 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
soulx 0:b502ea2d6ebb 562 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
soulx 0:b502ea2d6ebb 563 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
soulx 0:b502ea2d6ebb 564 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
soulx 0:b502ea2d6ebb 565 // the accelerometer biases calculated above must be divided by 8.
soulx 0:b502ea2d6ebb 566
soulx 0:b502ea2d6ebb 567 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
soulx 0:b502ea2d6ebb 568 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
soulx 0:b502ea2d6ebb 569 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
soulx 0:b502ea2d6ebb 570 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
soulx 0:b502ea2d6ebb 571 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
soulx 0:b502ea2d6ebb 572 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
soulx 0:b502ea2d6ebb 573 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
soulx 0:b502ea2d6ebb 574
soulx 0:b502ea2d6ebb 575 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
soulx 0:b502ea2d6ebb 576 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
soulx 0:b502ea2d6ebb 577
soulx 0:b502ea2d6ebb 578 for(ii = 0; ii < 3; ii++) {
soulx 0:b502ea2d6ebb 579 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
soulx 0:b502ea2d6ebb 580 }
soulx 0:b502ea2d6ebb 581
soulx 0:b502ea2d6ebb 582 // Construct total accelerometer bias, including calculated average accelerometer bias from above
soulx 0:b502ea2d6ebb 583 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
soulx 0:b502ea2d6ebb 584 accel_bias_reg[1] -= (accel_bias[1]/8);
soulx 0:b502ea2d6ebb 585 accel_bias_reg[2] -= (accel_bias[2]/8);
soulx 0:b502ea2d6ebb 586
soulx 0:b502ea2d6ebb 587 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
soulx 0:b502ea2d6ebb 588 data[1] = (accel_bias_reg[0]) & 0xFF;
soulx 0:b502ea2d6ebb 589 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
soulx 0:b502ea2d6ebb 590 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
soulx 0:b502ea2d6ebb 591 data[3] = (accel_bias_reg[1]) & 0xFF;
soulx 0:b502ea2d6ebb 592 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
soulx 0:b502ea2d6ebb 593 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
soulx 0:b502ea2d6ebb 594 data[5] = (accel_bias_reg[2]) & 0xFF;
soulx 0:b502ea2d6ebb 595 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
soulx 0:b502ea2d6ebb 596
soulx 0:b502ea2d6ebb 597 // Apparently this is not working for the acceleration biases in the MPU-9250
soulx 0:b502ea2d6ebb 598 // Are we handling the temperature correction bit properly?
soulx 0:b502ea2d6ebb 599 // Push accelerometer biases to hardware registers
soulx 0:b502ea2d6ebb 600 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
soulx 0:b502ea2d6ebb 601 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
soulx 0:b502ea2d6ebb 602 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
soulx 0:b502ea2d6ebb 603 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
soulx 0:b502ea2d6ebb 604 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
soulx 0:b502ea2d6ebb 605 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
soulx 0:b502ea2d6ebb 606 */
soulx 0:b502ea2d6ebb 607 // Output scaled accelerometer biases for manual subtraction in the main program
soulx 0:b502ea2d6ebb 608 accelBias[0] = (float)accel_bias[0]/(float)accelsensitivity;
soulx 0:b502ea2d6ebb 609 accelBias[1] = (float)accel_bias[1]/(float)accelsensitivity;
soulx 0:b502ea2d6ebb 610 accelBias[2] = (float)accel_bias[2]/(float)accelsensitivity;
soulx 0:b502ea2d6ebb 611 }
soulx 0:b502ea2d6ebb 612
soulx 0:b502ea2d6ebb 613
soulx 0:b502ea2d6ebb 614 // Accelerometer and gyroscope self test; check calibration wrt factory settings
soulx 0:b502ea2d6ebb 615 void MPU9250::MPU9250SelfTest() // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
soulx 0:b502ea2d6ebb 616 {
soulx 0:b502ea2d6ebb 617 //float destination[6] = {0,0,0,0,0,0};
soulx 0:b502ea2d6ebb 618 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
soulx 0:b502ea2d6ebb 619 uint8_t selfTest[6];
soulx 0:b502ea2d6ebb 620 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3];
soulx 0:b502ea2d6ebb 621 float factoryTrim[6];
soulx 0:b502ea2d6ebb 622 uint8_t FS = 0;
soulx 0:b502ea2d6ebb 623
soulx 0:b502ea2d6ebb 624 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
soulx 0:b502ea2d6ebb 625 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
soulx 0:b502ea2d6ebb 626 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
soulx 0:b502ea2d6ebb 627 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
soulx 0:b502ea2d6ebb 628 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
soulx 0:b502ea2d6ebb 629
soulx 0:b502ea2d6ebb 630 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
soulx 0:b502ea2d6ebb 631
soulx 0:b502ea2d6ebb 632 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
soulx 0:b502ea2d6ebb 633 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 634 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 635 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 636
soulx 0:b502ea2d6ebb 637 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
soulx 0:b502ea2d6ebb 638 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 639 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 640 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 641 }
soulx 0:b502ea2d6ebb 642
soulx 0:b502ea2d6ebb 643 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
soulx 0:b502ea2d6ebb 644 aAvg[ii] /= 200;
soulx 0:b502ea2d6ebb 645 gAvg[ii] /= 200;
soulx 0:b502ea2d6ebb 646 }
soulx 0:b502ea2d6ebb 647
soulx 0:b502ea2d6ebb 648 // Configure the accelerometer for self-test
soulx 0:b502ea2d6ebb 649 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
soulx 0:b502ea2d6ebb 650 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
soulx 0:b502ea2d6ebb 651 //delay(25); // Delay a while to let the device stabilize
soulx 0:b502ea2d6ebb 652
soulx 0:b502ea2d6ebb 653 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
soulx 0:b502ea2d6ebb 654
soulx 0:b502ea2d6ebb 655 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
soulx 0:b502ea2d6ebb 656 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 657 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 658 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 659
soulx 0:b502ea2d6ebb 660 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
soulx 0:b502ea2d6ebb 661 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
soulx 0:b502ea2d6ebb 662 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
soulx 0:b502ea2d6ebb 663 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
soulx 0:b502ea2d6ebb 664 }
soulx 0:b502ea2d6ebb 665
soulx 0:b502ea2d6ebb 666 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
soulx 0:b502ea2d6ebb 667 aSTAvg[ii] /= 200;
soulx 0:b502ea2d6ebb 668 gSTAvg[ii] /= 200;
soulx 0:b502ea2d6ebb 669 }
soulx 0:b502ea2d6ebb 670
soulx 0:b502ea2d6ebb 671 // Configure the gyro and accelerometer for normal operation
soulx 0:b502ea2d6ebb 672 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
soulx 0:b502ea2d6ebb 673 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
soulx 0:b502ea2d6ebb 674 //delay(25); // Delay a while to let the device stabilize
soulx 0:b502ea2d6ebb 675
soulx 0:b502ea2d6ebb 676 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
soulx 0:b502ea2d6ebb 677 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
soulx 0:b502ea2d6ebb 678 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
soulx 0:b502ea2d6ebb 679 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
soulx 0:b502ea2d6ebb 680 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
soulx 0:b502ea2d6ebb 681 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
soulx 0:b502ea2d6ebb 682 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
soulx 0:b502ea2d6ebb 683
soulx 0:b502ea2d6ebb 684 // Retrieve factory self-test value from self-test code reads
soulx 0:b502ea2d6ebb 685 factoryTrim[0] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[0] - (float)1.0) )); // FT[Xa] factory trim calculation
soulx 0:b502ea2d6ebb 686 factoryTrim[1] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[1] - (float)1.0) )); // FT[Ya] factory trim calculation
soulx 0:b502ea2d6ebb 687 factoryTrim[2] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[2] - (float)1.0) )); // FT[Za] factory trim calculation
soulx 0:b502ea2d6ebb 688 factoryTrim[3] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[3] - (float)1.0) )); // FT[Xg] factory trim calculation
soulx 0:b502ea2d6ebb 689 factoryTrim[4] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[4] - (float)1.0) )); // FT[Yg] factory trim calculation
soulx 0:b502ea2d6ebb 690 factoryTrim[5] = (float)(2620/1<<FS)*(pow( (float)1.01 , ((float)selfTest[5] - (float)1.0) )); // FT[Zg] factory trim calculation
soulx 0:b502ea2d6ebb 691
soulx 0:b502ea2d6ebb 692 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
soulx 0:b502ea2d6ebb 693 // To get percent, must multiply by 100
soulx 0:b502ea2d6ebb 694 for (int i = 0; i < 3; i++) {
soulx 0:b502ea2d6ebb 695 SelfTest[i] = (float)100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
soulx 0:b502ea2d6ebb 696 SelfTest[i+3] = (float)100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
soulx 0:b502ea2d6ebb 697 }
soulx 0:b502ea2d6ebb 698
soulx 0:b502ea2d6ebb 699 }