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.
MPU9250.cpp
00001 #include "MPU9250.h" 00002 00003 00004 uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G 00005 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS 00006 uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution 00007 uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR 00008 float aRes, gRes, mRes; // scale resolutions per LSB for the sensors 00009 00010 //Set up I2C, (SDA,SCL) 00011 I2C i2c(PB_9, PB_8); 00012 00013 DigitalOut myled(LED1); 00014 00015 // Pin definitions 00016 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 00017 00018 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00019 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00020 int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output 00021 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias 00022 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00023 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 00024 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00025 float temperature; 00026 float SelfTest[6]; 00027 00028 int delt_t = 0; // used to control display output rate 00029 int _count = 0; // used to control display output rate 00030 00031 // parameters for 6 DoF sensor fusion calculations 00032 float PI = 3.14159265358979323846f; 00033 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 00034 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00035 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00036 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 00037 #define Kp 2.0f * 5.0f // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral 00038 #define Ki 0.0f 00039 00040 float pitch, yaw, roll; 00041 float vx, vy, vz; 00042 float deltat = 0.0f; // integration interval for both filter schemes 00043 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00044 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00045 float v_trans[3] = {0.0f, 0.0f, 0.0f}; // vector to hold translative velocities 00046 float a_old[3] = {0.00f, 0.00f, 0.00f}; 00047 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 00048 00049 accData_t myData; 00050 Timer t; 00051 00052 #define SAMPLE_TIME 100 00053 00054 #define STEP_NUMBER 5 00055 float sum = 0; 00056 uint32_t sumCount = 0; 00057 char buffer[14]; 00058 float ax_sum = 0; 00059 static float vx_buffer[STEP_NUMBER]; 00060 static int8_t stepCounter = 0; 00061 00062 00063 // MPU9250-Constructor 00064 MPU9250::MPU9250(Serial* serialPtr) 00065 { 00066 pc = serialPtr; 00067 imuSetup(); 00068 vx_old = 0; 00069 } 00070 00071 00072 00073 //=================================================================================================================== 00074 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00075 //=================================================================================================================== 00076 00077 void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00078 { 00079 char data_write[2]; 00080 data_write[0] = subAddress; 00081 data_write[1] = data; 00082 i2c.write(address, data_write, 2, 0); 00083 } 00084 00085 char MPU9250::readByte(uint8_t address, uint8_t subAddress) 00086 { 00087 char data[1]; // `data` will store the register data 00088 char data_write[1]; 00089 data_write[0] = subAddress; 00090 i2c.write(address, data_write, 1, 1); // no stop 00091 i2c.read(address, data, 1, 0); 00092 return data[0]; 00093 } 00094 00095 void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00096 { 00097 char data[14]; 00098 char data_write[1]; 00099 data_write[0] = subAddress; 00100 i2c.write(address, data_write, 1, 1); // no stop 00101 i2c.read(address, data, count, 0); 00102 for(int ii = 0; ii < count; ii++) { 00103 dest[ii] = data[ii]; 00104 } 00105 } 00106 00107 00108 void MPU9250::getMres() 00109 { 00110 switch (Mscale) { 00111 // Possible magnetometer scales (and their register bit settings) are: 00112 // 14 bit resolution (0) and 16 bit resolution (1) 00113 case MFS_14BITS: 00114 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss 00115 break; 00116 case MFS_16BITS: 00117 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss 00118 break; 00119 } 00120 } 00121 00122 00123 void MPU9250::getGres() 00124 { 00125 switch (Gscale) { 00126 // Possible gyro scales (and their register bit settings) are: 00127 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00128 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00129 case GFS_250DPS: 00130 gRes = 250.0/32768.0; 00131 break; 00132 case GFS_500DPS: 00133 gRes = 500.0/32768.0; 00134 break; 00135 case GFS_1000DPS: 00136 gRes = 1000.0/32768.0; 00137 break; 00138 case GFS_2000DPS: 00139 gRes = 2000.0/32768.0; 00140 break; 00141 } 00142 } 00143 00144 00145 void MPU9250::getAres() 00146 { 00147 switch (Ascale) { 00148 // Possible accelerometer scales (and their register bit settings) are: 00149 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00150 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00151 case AFS_2G: 00152 aRes = 2.0/32768.0; 00153 break; 00154 case AFS_4G: 00155 aRes = 4.0/32768.0; 00156 break; 00157 case AFS_8G: 00158 aRes = 8.0/32768.0; 00159 break; 00160 case AFS_16G: 00161 aRes = 16.0/32768.0; 00162 break; 00163 } 00164 } 00165 00166 00167 void MPU9250::readAccelData(int16_t * destination) 00168 { 00169 uint8_t rawData[6]; // x/y/z accel register data stored here 00170 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00171 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00172 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00173 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00174 } 00175 00176 void MPU9250::readGyroData(int16_t * destination) 00177 { 00178 uint8_t rawData[6]; // x/y/z gyro register data stored here 00179 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00180 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00181 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00182 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00183 } 00184 00185 void MPU9250::readMagData(int16_t * destination) 00186 { 00187 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 00188 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 00189 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 00190 uint8_t c = rawData[6]; // End data read by reading ST2 register 00191 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data 00192 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value 00193 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian 00194 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 00195 } 00196 } 00197 } 00198 00199 int16_t MPU9250::readTempData() 00200 { 00201 uint8_t rawData[2]; // x/y/z gyro register data stored here 00202 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00203 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00204 } 00205 00206 00207 void MPU9250::resetMPU9250() 00208 { 00209 // reset device 00210 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00211 wait(0.1); 00212 } 00213 00214 void MPU9250::initAK8963(float * destination) 00215 { 00216 // First extract the factory calibration for each magnetometer axis 00217 uint8_t rawData[3]; // x/y/z gyro calibration data stored here 00218 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00219 wait(0.01); 00220 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 00221 wait(0.01); 00222 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 00223 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. 00224 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; 00225 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; 00226 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 00227 wait(0.01); 00228 // Configure the magnetometer for continuous read and highest resolution 00229 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 00230 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 00231 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 00232 wait(0.01); 00233 } 00234 00235 00236 void MPU9250::initMPU9250() 00237 { 00238 // Initialize MPU9250 device 00239 // wake up device 00240 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00241 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00242 00243 // get stable time source 00244 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00245 00246 // Configure Gyro and Accelerometer 00247 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00248 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00249 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00250 writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 00251 00252 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00253 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00254 00255 // Set gyroscope full scale range 00256 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00257 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 00258 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00259 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00260 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00261 00262 // Set accelerometer configuration 00263 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 00264 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00265 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00266 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00267 00268 // Set accelerometer sample rate configuration 00269 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 00270 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 00271 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 00272 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 00273 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 00274 00275 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 00276 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 00277 00278 // Configure Interrupts and Bypass Enable 00279 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00280 // can join the I2C bus and all can be controlled by the Arduino as master 00281 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 00282 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00283 } 00284 00285 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00286 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00287 void MPU9250::calibrateMPU9250(float * dest1, float * dest2) 00288 { 00289 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00290 uint16_t ii, packet_count, fifo_count; 00291 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00292 00293 // reset device, reset all registers, clear gyro and accelerometer bias registers 00294 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00295 wait(0.1); 00296 00297 // get stable time source 00298 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00299 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 00300 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 00301 wait(0.2); 00302 00303 // Configure device for bias calculation 00304 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00305 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00306 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00307 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00308 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00309 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00310 wait(0.015); 00311 00312 // Configure MPU9250 gyro and accelerometer for bias calculation 00313 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00314 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00315 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00316 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00317 00318 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00319 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00320 00321 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00322 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00323 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) 00324 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes 00325 00326 // At end of sample accumulation, turn off FIFO sensor read 00327 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00328 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00329 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00330 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00331 00332 for (ii = 0; ii < packet_count; ii++) { 00333 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00334 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00335 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00336 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00337 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00338 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00339 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00340 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00341 00342 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00343 accel_bias[1] += (int32_t) accel_temp[1]; 00344 accel_bias[2] += (int32_t) accel_temp[2]; 00345 gyro_bias[0] += (int32_t) gyro_temp[0]; 00346 gyro_bias[1] += (int32_t) gyro_temp[1]; 00347 gyro_bias[2] += (int32_t) gyro_temp[2]; 00348 00349 } 00350 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00351 accel_bias[1] /= (int32_t) packet_count; 00352 accel_bias[2] /= (int32_t) packet_count; 00353 gyro_bias[0] /= (int32_t) packet_count; 00354 gyro_bias[1] /= (int32_t) packet_count; 00355 gyro_bias[2] /= (int32_t) packet_count; 00356 00357 if(accel_bias[2] > 0L) { 00358 accel_bias[2] -= (int32_t) accelsensitivity; // Remove gravity from the z-axis accelerometer bias calculation 00359 } else { 00360 accel_bias[2] += (int32_t) accelsensitivity; 00361 } 00362 00363 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00364 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 00365 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00366 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00367 data[3] = (-gyro_bias[1]/4) & 0xFF; 00368 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00369 data[5] = (-gyro_bias[2]/4) & 0xFF; 00370 00371 /// Push gyro biases to hardware registers 00372 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 00373 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 00374 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 00375 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 00376 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 00377 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 00378 */ 00379 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00380 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00381 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00382 00383 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00384 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00385 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00386 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00387 // the accelerometer biases calculated above must be divided by 8. 00388 00389 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00390 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00391 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00392 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00393 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00394 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00395 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00396 00397 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00398 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00399 00400 for(ii = 0; ii < 3; ii++) { 00401 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00402 } 00403 00404 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00405 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00406 accel_bias_reg[1] -= (accel_bias[1]/8); 00407 accel_bias_reg[2] -= (accel_bias[2]/8); 00408 00409 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00410 data[1] = (accel_bias_reg[0]) & 0xFF; 00411 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00412 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00413 data[3] = (accel_bias_reg[1]) & 0xFF; 00414 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00415 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00416 data[5] = (accel_bias_reg[2]) & 0xFF; 00417 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00418 00419 // Apparently this is not working for the acceleration biases in the MPU-9250 00420 // Are we handling the temperature correction bit properly? 00421 // Push accelerometer biases to hardware registers 00422 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 00423 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 00424 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 00425 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 00426 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 00427 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 00428 */ 00429 // Output scaled accelerometer biases for manual subtraction in the main program 00430 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00431 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00432 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00433 } 00434 00435 00436 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00437 void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00438 { 00439 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 00440 uint8_t selfTest[6]; 00441 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 00442 float factoryTrim[6]; 00443 uint8_t FS = 0; 00444 00445 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 00446 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 00447 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps 00448 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz 00449 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g 00450 00451 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer 00452 00453 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00454 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00455 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00456 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00457 00458 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00459 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00460 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00461 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00462 } 00463 00464 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings 00465 aAvg[ii] /= 200; 00466 gAvg[ii] /= 200; 00467 } 00468 00469 // Configure the accelerometer for self-test 00470 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g 00471 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00472 wait(0.025); // Delay a while to let the device stabilize 00473 00474 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer 00475 00476 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00477 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00478 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00479 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00480 00481 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00482 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00483 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00484 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00485 } 00486 00487 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings 00488 aSTAvg[ii] /= 200; 00489 gSTAvg[ii] /= 200; 00490 } 00491 00492 // Configure the gyro and accelerometer for normal operation 00493 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); 00494 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); 00495 wait(0.025); // Delay a while to let the device stabilize 00496 00497 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg 00498 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results 00499 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results 00500 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results 00501 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results 00502 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results 00503 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results 00504 00505 // Retrieve factory self-test value from self-test code reads 00506 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation 00507 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation 00508 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation 00509 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation 00510 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation 00511 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01, ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation 00512 00513 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00514 // To get percent, must multiply by 100 00515 for (int i = 0; i < 3; i++) { 00516 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences 00517 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences 00518 } 00519 00520 } 00521 00522 00523 00524 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00525 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00526 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 00527 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00528 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00529 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00530 void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 00531 { 00532 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00533 float norm; 00534 float hx, hy, _2bx, _2bz; 00535 float s1, s2, s3, s4; 00536 float qDot1, qDot2, qDot3, qDot4; 00537 00538 // Auxiliary variables to avoid repeated arithmetic 00539 float _2q1mx; 00540 float _2q1my; 00541 float _2q1mz; 00542 float _2q2mx; 00543 float _4bx; 00544 float _4bz; 00545 float _2q1 = 2.0f * q1; 00546 float _2q2 = 2.0f * q2; 00547 float _2q3 = 2.0f * q3; 00548 float _2q4 = 2.0f * q4; 00549 float _2q1q3 = 2.0f * q1 * q3; 00550 float _2q3q4 = 2.0f * q3 * q4; 00551 float q1q1 = q1 * q1; 00552 float q1q2 = q1 * q2; 00553 float q1q3 = q1 * q3; 00554 float q1q4 = q1 * q4; 00555 float q2q2 = q2 * q2; 00556 float q2q3 = q2 * q3; 00557 float q2q4 = q2 * q4; 00558 float q3q3 = q3 * q3; 00559 float q3q4 = q3 * q4; 00560 float q4q4 = q4 * q4; 00561 00562 // Normalise accelerometer measurement 00563 norm = sqrt(ax * ax + ay * ay + az * az); 00564 if (norm == 0.0f) return; // handle NaN 00565 norm = 1.0f/norm; 00566 ax *= norm; 00567 ay *= norm; 00568 az *= norm; 00569 00570 // Normalise magnetometer measurement 00571 norm = sqrt(mx * mx + my * my + mz * mz); 00572 if (norm == 0.0f) return; // handle NaN 00573 norm = 1.0f/norm; 00574 mx *= norm; 00575 my *= norm; 00576 mz *= norm; 00577 00578 // Reference direction of Earth's magnetic field 00579 _2q1mx = 2.0f * q1 * mx; 00580 _2q1my = 2.0f * q1 * my; 00581 _2q1mz = 2.0f * q1 * mz; 00582 _2q2mx = 2.0f * q2 * mx; 00583 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; 00584 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; 00585 _2bx = sqrt(hx * hx + hy * hy); 00586 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; 00587 _4bx = 2.0f * _2bx; 00588 _4bz = 2.0f * _2bz; 00589 00590 // Gradient decent algorithm corrective step 00591 s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 00592 s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 00593 s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 00594 s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); 00595 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude 00596 norm = 1.0f/norm; 00597 s1 *= norm; 00598 s2 *= norm; 00599 s3 *= norm; 00600 s4 *= norm; 00601 00602 // Compute rate of change of quaternion 00603 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; 00604 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; 00605 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; 00606 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; 00607 00608 // Integrate to yield quaternion 00609 q1 += qDot1 * deltat; 00610 q2 += qDot2 * deltat; 00611 q3 += qDot3 * deltat; 00612 q4 += qDot4 * deltat; 00613 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00614 norm = 1.0f/norm; 00615 q[0] = q1 * norm; 00616 q[1] = q2 * norm; 00617 q[2] = q3 * norm; 00618 q[3] = q4 * norm; 00619 00620 } 00621 00622 00623 void MPU9250::readIMU() 00624 { 00625 // If intPin goes high, all data registers have new data 00626 if(readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 00627 00628 readAccelData(accelCount); // Read the x/y/z adc values 00629 // Now we'll calculate the accleration value into actual g's 00630 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set 00631 ay = (float)accelCount[1]*aRes - accelBias[1]; 00632 az = (float)accelCount[2]*aRes - accelBias[2]; 00633 00634 readGyroData(gyroCount); // Read the x/y/z adc values 00635 // Calculate the gyro value into actual degrees per second 00636 gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set 00637 gy = (float)gyroCount[1]*gRes - gyroBias[1]; 00638 gz = (float)gyroCount[2]*gRes - gyroBias[2]; 00639 00640 readMagData(magCount); // Read the x/y/z adc values 00641 // Calculate the magnetometer values in milliGauss 00642 // Include factory calibration per data sheet and user environmental corrections 00643 mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set 00644 my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 00645 mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 00646 } 00647 00648 00649 00650 //pc.printf("ax, ay, az, delta_t;%f;%f;%f;%f\n\r", ax, ay, az*GRAVITATION + GRAVITATION, deltat); 00651 00652 Now = t.read_us(); 00653 00654 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00655 lastUpdate = Now; 00656 00657 //pc.printf("%f,%f,%f,%f\n\r",ax, ay, az, deltat); 00658 00659 00660 sum += deltat; 00661 sumCount++; 00662 00663 // Pass gyro rate as rad/s 00664 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00665 //mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 00666 00667 // Serial print and/or display at 0.5 s rate independent of data rates 00668 delt_t = t.read_ms() - _count; 00669 //pc.printf("Zeit intern: %d\n\r", t.read_ms()); 00670 } 00671 00672 00673 00674 /*//----------------------------------------- 00675 // Update displayed value 00676 if (delt_t > SAMPLE_TIME) { 00677 00678 00679 00680 //pc.printf("vx, vy, vz: %f %f %f\n\r", v_trans[0], v_trans[1], v_trans[2]); 00681 00682 00683 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]); 00684 pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00685 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]); 00686 pitch *= 180.0f / PI; 00687 yaw *= 180.0f / PI; 00688 yaw -= 2.93f; // Declination at 8572 Berg TG: +2° 56' 00689 roll *= 180.0f / PI; 00690 00691 00692 00693 myled= !myled; 00694 _count = t.read_ms(); 00695 00696 if(_count > 1<<21) { 00697 t.start(); // start the timer over again if ~30 minutes has passed 00698 _count = 0; 00699 deltat= 0; 00700 lastUpdate = t.read_us(); 00701 } 00702 sum = 0; 00703 sumCount = 0; 00704 }*/ 00705 00706 00707 00708 void MPU9250::imuSetup() 00709 { 00710 //Set up I2C 00711 i2c.frequency(400000); // use fast (400 kHz) I2C 00712 00713 pc->printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); 00714 00715 t.start(); 00716 // lcd.setBrightness(0.05); 00717 00718 00719 // Read the WHO_AM_I register, this is a good test of communication 00720 uint8_t whoami = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 00721 pc->printf("I AM 0x%x\n\r", whoami); 00722 pc->printf("I SHOULD BE 0x71\n\r"); 00723 00724 if (whoami == 0x71) { // WHO_AM_I should always be 0x68 00725 pc->printf("MPU9250 WHO_AM_I is 0x%x\n\r", whoami); 00726 pc->printf("MPU9250 is online...\n\r"); 00727 sprintf(buffer, "0x%x", whoami); 00728 wait(1); 00729 00730 resetMPU9250(); // Reset registers to default in preparation for device calibration 00731 MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values 00732 pc->printf("x-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[0]); 00733 pc->printf("y-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[1]); 00734 pc->printf("z-axis self test: acceleration trim within : %f % of factory value\n\r", SelfTest[2]); 00735 pc->printf("x-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[3]); 00736 pc->printf("y-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[4]); 00737 pc->printf("z-axis self test: gyration trim within : %f % of factory value\n\r", SelfTest[5]); 00738 calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00739 pc->printf("x gyro bias = %f\n\r", gyroBias[0]); 00740 pc->printf("y gyro bias = %f\n\r", gyroBias[1]); 00741 pc->printf("z gyro bias = %f\n\r", gyroBias[2]); 00742 pc->printf("x accel bias = %f\n\r", accelBias[0]); 00743 pc->printf("y accel bias = %f\n\r", accelBias[1]); 00744 pc->printf("z accel bias = %f\n\r", accelBias[2]); 00745 wait(2); 00746 initMPU9250(); 00747 pc->printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00748 initAK8963(magCalibration); 00749 pc->printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer 00750 pc->printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1<<Ascale)); 00751 pc->printf("Gyroscope full-scale range = %f deg/s\n\r", 250.0f*(float)(1<<Gscale)); 00752 if(Mscale == 0) pc->printf("Magnetometer resolution = 14 bits\n\r"); 00753 if(Mscale == 1) pc->printf("Magnetometer resolution = 16 bits\n\r"); 00754 if(Mmode == 2) pc->printf("Magnetometer ODR = 8 Hz\n\r"); 00755 if(Mmode == 6) pc->printf("Magnetometer ODR = 100 Hz\n\r"); 00756 wait(1); 00757 } else { 00758 pc->printf("Could not connect to MPU9250: \n\r"); 00759 pc->printf("%#x \n", whoami); 00760 sprintf(buffer, "WHO_AM_I 0x%x", whoami); 00761 00762 while(1) { 00763 // Loop forever if communication doesn't happen 00764 pc->printf("no IMU detected (verify if it's plugged in)\n\r"); 00765 } 00766 } 00767 00768 getAres(); // Get accelerometer sensitivity 00769 getGres(); // Get gyro sensitivity 00770 getMres(); // Get magnetometer sensitivity 00771 pc->printf("Accelerometer sensitivity is %f LSB/g \n\r", 1.0f/aRes); 00772 pc->printf("Gyroscope sensitivity is %f LSB/deg/s \n\r", 1.0f/gRes); 00773 pc->printf("Magnetometer sensitivity is %f LSB/G \n\r", 1.0f/mRes); 00774 magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated 00775 magbias[1] = +120.; // User environmental x-axis correction in milliGauss 00776 magbias[2] = +125.; // User environmental x-axis correction in milliGauss 00777 } 00778 00779 00780 // N Werte sammeln, Integrale aufsummieren 00781 /*float MPU9250::getMedianAcc(){ 00782 int8_t i; 00783 ax_sum = 0; 00784 for (i=0; i<STEP_NUMBER; i++) { 00785 readIMU(); 00786 //pc.printf("Zeit extern: %d\n\n\r", t.read_ms()); 00787 pc.printf("i=%d: ax=%f\n\r", i, ax); 00788 ax_sum += ax; 00789 } 00790 pc.printf("Summe: %f\n\n\r", ax_sum/steps); 00791 return ax_sum/steps; 00792 }*/ 00793 00794 00795 // BufferArray-Variante 00796 float MPU9250::getVBuffer() 00797 { 00798 // Save the last ax value before readIMU() is executed 00799 float ax_old = ax; 00800 00801 // Save the last vx value 00802 if (stepCounter == 0) { 00803 vx_old = vx_buffer[STEP_NUMBER-1]; 00804 } 00805 else{ 00806 vx_old = vx_buffer[stepCounter - 1]; 00807 } 00808 00809 00810 // Sets new ax value 00811 readIMU(); 00812 00813 00814 // Calculate Integration Step of new and old value 00815 vx_buffer[stepCounter] = vx_old + deltat*0.5f*(ax + ax_old)/GRAVITATION; 00816 00817 int i; 00818 float vx_median = 0; 00819 for (i=0; i<STEP_NUMBER; i++) { 00820 vx_median += vx_buffer[i]; 00821 //pc.printf("%d: %f\n\r", i, vx_buffer[i]); 00822 } 00823 //pc.printf("\n\r"); 00824 //pc.printf("%f,%f,%f,%f\n\r", ax, vx_median/STEP_NUMBER, vx_buffer[stepCounter], deltat); 00825 00826 stepCounter++; 00827 if (stepCounter >= STEP_NUMBER) { 00828 stepCounter = 0; 00829 } 00830 return vx_median/STEP_NUMBER; 00831 }
Generated on Thu Jul 14 2022 14:36:20 by
