as
Dependencies: CommonTypes ESC Matrix PID Servo kalman mbed-rtos mbed
Fork of Nucleo_MPU_9250_ by
MPU9250.cpp@0:89cf0851969b, 2018-06-26 (annotated)
- Committer:
- AlanHuchin
- Date:
- Tue Jun 26 18:24:45 2018 +0000
- Revision:
- 0:89cf0851969b
hello
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
AlanHuchin | 0:89cf0851969b | 1 | #include "MPU9250.h" |
AlanHuchin | 0:89cf0851969b | 2 | |
AlanHuchin | 0:89cf0851969b | 3 | // Set initial input parameters |
AlanHuchin | 0:89cf0851969b | 4 | enum Ascale { |
AlanHuchin | 0:89cf0851969b | 5 | AFS_2G = 0, |
AlanHuchin | 0:89cf0851969b | 6 | AFS_4G, |
AlanHuchin | 0:89cf0851969b | 7 | AFS_8G, |
AlanHuchin | 0:89cf0851969b | 8 | AFS_16G |
AlanHuchin | 0:89cf0851969b | 9 | }; |
AlanHuchin | 0:89cf0851969b | 10 | |
AlanHuchin | 0:89cf0851969b | 11 | enum Gscale { |
AlanHuchin | 0:89cf0851969b | 12 | GFS_250DPS = 0, |
AlanHuchin | 0:89cf0851969b | 13 | GFS_500DPS, |
AlanHuchin | 0:89cf0851969b | 14 | GFS_1000DPS, |
AlanHuchin | 0:89cf0851969b | 15 | GFS_2000DPS |
AlanHuchin | 0:89cf0851969b | 16 | }; |
AlanHuchin | 0:89cf0851969b | 17 | |
AlanHuchin | 0:89cf0851969b | 18 | enum Mscale { |
AlanHuchin | 0:89cf0851969b | 19 | MFS_14BITS = 0, // 0.6 mG per LSB |
AlanHuchin | 0:89cf0851969b | 20 | MFS_16BITS // 0.15 mG per LSB |
AlanHuchin | 0:89cf0851969b | 21 | }; |
AlanHuchin | 0:89cf0851969b | 22 | |
AlanHuchin | 0:89cf0851969b | 23 | float ax,ay,az; |
AlanHuchin | 0:89cf0851969b | 24 | float gx,gy,gz; |
AlanHuchin | 0:89cf0851969b | 25 | float mx,my,mz; |
AlanHuchin | 0:89cf0851969b | 26 | int16_t accelData[3],gyroData[3],tempData; |
AlanHuchin | 0:89cf0851969b | 27 | float accelBias[3] = {0, 0, 0}; // Bias corrections for acc |
AlanHuchin | 0:89cf0851969b | 28 | float gyroBias[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 29 | extern float magCalibration[3]= {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 30 | extern float magbias[3]= {0, 0, 0}, magScale[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 31 | float SelfTest[6]; |
AlanHuchin | 0:89cf0851969b | 32 | |
AlanHuchin | 0:89cf0851969b | 33 | int delt_t = 0; // used to control display output rate |
AlanHuchin | 0:89cf0851969b | 34 | int count = 0; // used to control display output rate |
AlanHuchin | 0:89cf0851969b | 35 | |
AlanHuchin | 0:89cf0851969b | 36 | // parameters for 6 DoF sensor fusion calculations |
AlanHuchin | 0:89cf0851969b | 37 | float PI = 3.14159265358979323846f; |
AlanHuchin | 0:89cf0851969b | 38 | 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 |
AlanHuchin | 0:89cf0851969b | 39 | float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta |
AlanHuchin | 0:89cf0851969b | 40 | float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) |
AlanHuchin | 0:89cf0851969b | 41 | 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 |
AlanHuchin | 0:89cf0851969b | 42 | #define Kp 0.98 // these are the free parameters in the Mahony filter and fusion scheme, Kp for proportional feedback, Ki for integral |
AlanHuchin | 0:89cf0851969b | 43 | #define Ki 0.0000001f |
AlanHuchin | 0:89cf0851969b | 44 | |
AlanHuchin | 0:89cf0851969b | 45 | float pitch, yaw, roll; |
AlanHuchin | 0:89cf0851969b | 46 | float deltat = 0.0f; // integration interval for both filter schemes |
AlanHuchin | 0:89cf0851969b | 47 | int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval |
AlanHuchin | 0:89cf0851969b | 48 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion |
AlanHuchin | 0:89cf0851969b | 49 | float eInt[3] = {0.0f, 0.0f, 0.0f}; |
AlanHuchin | 0:89cf0851969b | 50 | |
AlanHuchin | 0:89cf0851969b | 51 | uint8_t Ascale = AFS_16G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G |
AlanHuchin | 0:89cf0851969b | 52 | uint8_t Gscale = GFS_2000DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS |
AlanHuchin | 0:89cf0851969b | 53 | uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution |
AlanHuchin | 0:89cf0851969b | 54 | uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR |
AlanHuchin | 0:89cf0851969b | 55 | float aRes, gRes, mRes; |
AlanHuchin | 0:89cf0851969b | 56 | |
AlanHuchin | 0:89cf0851969b | 57 | MPU9250::MPU9250(PinName sda, PinName scl) : i2c(sda, scl) { |
AlanHuchin | 0:89cf0851969b | 58 | //this->setSleepMode(false); |
AlanHuchin | 0:89cf0851969b | 59 | i2c.frequency(400000); |
AlanHuchin | 0:89cf0851969b | 60 | //Initializations: |
AlanHuchin | 0:89cf0851969b | 61 | currentGyroRange = 0; |
AlanHuchin | 0:89cf0851969b | 62 | currentAcceleroRange=0; |
AlanHuchin | 0:89cf0851969b | 63 | } |
AlanHuchin | 0:89cf0851969b | 64 | |
AlanHuchin | 0:89cf0851969b | 65 | //-------------------------------------------------- |
AlanHuchin | 0:89cf0851969b | 66 | //--------------------CONFIG------------------------ |
AlanHuchin | 0:89cf0851969b | 67 | //-------------------------------------------------- |
AlanHuchin | 0:89cf0851969b | 68 | |
AlanHuchin | 0:89cf0851969b | 69 | void MPU9250::getAres() |
AlanHuchin | 0:89cf0851969b | 70 | { |
AlanHuchin | 0:89cf0851969b | 71 | switch(Ascale) |
AlanHuchin | 0:89cf0851969b | 72 | { |
AlanHuchin | 0:89cf0851969b | 73 | case AFS_2G: |
AlanHuchin | 0:89cf0851969b | 74 | aRes = 2.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 75 | break; |
AlanHuchin | 0:89cf0851969b | 76 | case AFS_4G: |
AlanHuchin | 0:89cf0851969b | 77 | aRes = 4.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 78 | break; |
AlanHuchin | 0:89cf0851969b | 79 | case AFS_8G: |
AlanHuchin | 0:89cf0851969b | 80 | aRes = 8.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 81 | break; |
AlanHuchin | 0:89cf0851969b | 82 | case AFS_16G: |
AlanHuchin | 0:89cf0851969b | 83 | aRes = 16.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 84 | break; |
AlanHuchin | 0:89cf0851969b | 85 | } |
AlanHuchin | 0:89cf0851969b | 86 | } |
AlanHuchin | 0:89cf0851969b | 87 | |
AlanHuchin | 0:89cf0851969b | 88 | void MPU9250::getGres() |
AlanHuchin | 0:89cf0851969b | 89 | { |
AlanHuchin | 0:89cf0851969b | 90 | switch(Gscale) |
AlanHuchin | 0:89cf0851969b | 91 | { |
AlanHuchin | 0:89cf0851969b | 92 | case GFS_250DPS: |
AlanHuchin | 0:89cf0851969b | 93 | gRes = 250.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 94 | break; |
AlanHuchin | 0:89cf0851969b | 95 | case GFS_500DPS: |
AlanHuchin | 0:89cf0851969b | 96 | gRes = 500.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 97 | break; |
AlanHuchin | 0:89cf0851969b | 98 | case GFS_1000DPS: |
AlanHuchin | 0:89cf0851969b | 99 | gRes = 1000.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 100 | break; |
AlanHuchin | 0:89cf0851969b | 101 | case GFS_2000DPS: |
AlanHuchin | 0:89cf0851969b | 102 | gRes = 2000.0/32768.0; |
AlanHuchin | 0:89cf0851969b | 103 | break; |
AlanHuchin | 0:89cf0851969b | 104 | } |
AlanHuchin | 0:89cf0851969b | 105 | } |
AlanHuchin | 0:89cf0851969b | 106 | |
AlanHuchin | 0:89cf0851969b | 107 | void MPU9250::getMres() { |
AlanHuchin | 0:89cf0851969b | 108 | switch (Mscale) |
AlanHuchin | 0:89cf0851969b | 109 | { |
AlanHuchin | 0:89cf0851969b | 110 | // Possible magnetometer scales (and their register bit settings) are: |
AlanHuchin | 0:89cf0851969b | 111 | // 14 bit resolution (0) and 16 bit resolution (1) |
AlanHuchin | 0:89cf0851969b | 112 | case MFS_14BITS: |
AlanHuchin | 0:89cf0851969b | 113 | mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss |
AlanHuchin | 0:89cf0851969b | 114 | break; |
AlanHuchin | 0:89cf0851969b | 115 | case MFS_16BITS: |
AlanHuchin | 0:89cf0851969b | 116 | mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss |
AlanHuchin | 0:89cf0851969b | 117 | break; |
AlanHuchin | 0:89cf0851969b | 118 | } |
AlanHuchin | 0:89cf0851969b | 119 | } |
AlanHuchin | 0:89cf0851969b | 120 | //-------------------------------------------------- |
AlanHuchin | 0:89cf0851969b | 121 | //-------------------General------------------------ |
AlanHuchin | 0:89cf0851969b | 122 | //-------------------------------------------------- |
AlanHuchin | 0:89cf0851969b | 123 | |
AlanHuchin | 0:89cf0851969b | 124 | void MPU9250::writeByte(uint8_t address, uint8_t subAddress, uint8_t data) |
AlanHuchin | 0:89cf0851969b | 125 | { |
AlanHuchin | 0:89cf0851969b | 126 | char data_write[2]; |
AlanHuchin | 0:89cf0851969b | 127 | data_write[0] = subAddress; |
AlanHuchin | 0:89cf0851969b | 128 | data_write[1] = data; |
AlanHuchin | 0:89cf0851969b | 129 | i2c.write(address, data_write, 2, 0); |
AlanHuchin | 0:89cf0851969b | 130 | } |
AlanHuchin | 0:89cf0851969b | 131 | |
AlanHuchin | 0:89cf0851969b | 132 | char MPU9250::readByte(uint8_t address, uint8_t subAddress) |
AlanHuchin | 0:89cf0851969b | 133 | { |
AlanHuchin | 0:89cf0851969b | 134 | char data[1]; // `data` will store the register data |
AlanHuchin | 0:89cf0851969b | 135 | char data_write[1]; |
AlanHuchin | 0:89cf0851969b | 136 | data_write[0] = subAddress; |
AlanHuchin | 0:89cf0851969b | 137 | i2c.write(address, data_write, 1, 1); // no stop |
AlanHuchin | 0:89cf0851969b | 138 | i2c.read(address, data, 1, 0); |
AlanHuchin | 0:89cf0851969b | 139 | return data[0]; |
AlanHuchin | 0:89cf0851969b | 140 | } |
AlanHuchin | 0:89cf0851969b | 141 | |
AlanHuchin | 0:89cf0851969b | 142 | void MPU9250::readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) |
AlanHuchin | 0:89cf0851969b | 143 | { |
AlanHuchin | 0:89cf0851969b | 144 | char data[14]; |
AlanHuchin | 0:89cf0851969b | 145 | char data_write[1]; |
AlanHuchin | 0:89cf0851969b | 146 | data_write[0] = subAddress; |
AlanHuchin | 0:89cf0851969b | 147 | i2c.write(address, data_write, 1, 1); // no stop |
AlanHuchin | 0:89cf0851969b | 148 | i2c.read(address, data, count, 0); |
AlanHuchin | 0:89cf0851969b | 149 | for(int ii = 0; ii < count; ii++) { |
AlanHuchin | 0:89cf0851969b | 150 | dest[ii] = data[ii]; |
AlanHuchin | 0:89cf0851969b | 151 | } |
AlanHuchin | 0:89cf0851969b | 152 | } |
AlanHuchin | 0:89cf0851969b | 153 | |
AlanHuchin | 0:89cf0851969b | 154 | |
AlanHuchin | 0:89cf0851969b | 155 | void MPU9250::readAccelData(int16_t * destination) |
AlanHuchin | 0:89cf0851969b | 156 | { |
AlanHuchin | 0:89cf0851969b | 157 | uint8_t rawData[6]; // x/y/z accel register data stored here |
AlanHuchin | 0:89cf0851969b | 158 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array |
AlanHuchin | 0:89cf0851969b | 159 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 160 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 161 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 162 | } |
AlanHuchin | 0:89cf0851969b | 163 | |
AlanHuchin | 0:89cf0851969b | 164 | void MPU9250::readGyroData(int16_t * destination) |
AlanHuchin | 0:89cf0851969b | 165 | { |
AlanHuchin | 0:89cf0851969b | 166 | uint8_t rawData[6]; // x/y/z gyro register data stored here |
AlanHuchin | 0:89cf0851969b | 167 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array |
AlanHuchin | 0:89cf0851969b | 168 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 169 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 170 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 171 | } |
AlanHuchin | 0:89cf0851969b | 172 | |
AlanHuchin | 0:89cf0851969b | 173 | void MPU9250::readMagData(int16_t * destination) |
AlanHuchin | 0:89cf0851969b | 174 | { |
AlanHuchin | 0:89cf0851969b | 175 | uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition |
AlanHuchin | 0:89cf0851969b | 176 | if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set |
AlanHuchin | 0:89cf0851969b | 177 | readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array |
AlanHuchin | 0:89cf0851969b | 178 | uint8_t c = rawData[6]; // End data read by reading ST2 register |
AlanHuchin | 0:89cf0851969b | 179 | if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data |
AlanHuchin | 0:89cf0851969b | 180 | destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 181 | destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian |
AlanHuchin | 0:89cf0851969b | 182 | destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; |
AlanHuchin | 0:89cf0851969b | 183 | } |
AlanHuchin | 0:89cf0851969b | 184 | } |
AlanHuchin | 0:89cf0851969b | 185 | } |
AlanHuchin | 0:89cf0851969b | 186 | |
AlanHuchin | 0:89cf0851969b | 187 | int16_t MPU9250::readTempData() |
AlanHuchin | 0:89cf0851969b | 188 | { |
AlanHuchin | 0:89cf0851969b | 189 | uint8_t rawData[2]; // x/y/z gyro register data stored here |
AlanHuchin | 0:89cf0851969b | 190 | readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array |
AlanHuchin | 0:89cf0851969b | 191 | return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value |
AlanHuchin | 0:89cf0851969b | 192 | } |
AlanHuchin | 0:89cf0851969b | 193 | |
AlanHuchin | 0:89cf0851969b | 194 | void MPU9250::resetMPU9250() { |
AlanHuchin | 0:89cf0851969b | 195 | // reset device |
AlanHuchin | 0:89cf0851969b | 196 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device |
AlanHuchin | 0:89cf0851969b | 197 | wait(0.1); |
AlanHuchin | 0:89cf0851969b | 198 | } |
AlanHuchin | 0:89cf0851969b | 199 | |
AlanHuchin | 0:89cf0851969b | 200 | void MPU9250::initAK8963(float * destination) |
AlanHuchin | 0:89cf0851969b | 201 | { |
AlanHuchin | 0:89cf0851969b | 202 | // First extract the factory calibration for each magnetometer axis |
AlanHuchin | 0:89cf0851969b | 203 | uint8_t rawData[3]; // x/y/z gyro calibration data stored here |
AlanHuchin | 0:89cf0851969b | 204 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer |
AlanHuchin | 0:89cf0851969b | 205 | wait(0.01); |
AlanHuchin | 0:89cf0851969b | 206 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode |
AlanHuchin | 0:89cf0851969b | 207 | wait(0.01); |
AlanHuchin | 0:89cf0851969b | 208 | readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values |
AlanHuchin | 0:89cf0851969b | 209 | destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. |
AlanHuchin | 0:89cf0851969b | 210 | destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; |
AlanHuchin | 0:89cf0851969b | 211 | destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; |
AlanHuchin | 0:89cf0851969b | 212 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer |
AlanHuchin | 0:89cf0851969b | 213 | wait(0.01); |
AlanHuchin | 0:89cf0851969b | 214 | // Configure the magnetometer for continuous read and highest resolution |
AlanHuchin | 0:89cf0851969b | 215 | // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, |
AlanHuchin | 0:89cf0851969b | 216 | // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates |
AlanHuchin | 0:89cf0851969b | 217 | writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR |
AlanHuchin | 0:89cf0851969b | 218 | wait(0.01); |
AlanHuchin | 0:89cf0851969b | 219 | } |
AlanHuchin | 0:89cf0851969b | 220 | |
AlanHuchin | 0:89cf0851969b | 221 | void MPU9250::initMPU9250() |
AlanHuchin | 0:89cf0851969b | 222 | { |
AlanHuchin | 0:89cf0851969b | 223 | // Initialize MPU9250 device |
AlanHuchin | 0:89cf0851969b | 224 | // wake up device |
AlanHuchin | 0:89cf0851969b | 225 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors |
AlanHuchin | 0:89cf0851969b | 226 | wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt |
AlanHuchin | 0:89cf0851969b | 227 | |
AlanHuchin | 0:89cf0851969b | 228 | // get stable time source |
AlanHuchin | 0:89cf0851969b | 229 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 |
AlanHuchin | 0:89cf0851969b | 230 | |
AlanHuchin | 0:89cf0851969b | 231 | // Configure Gyro and Accelerometer |
AlanHuchin | 0:89cf0851969b | 232 | // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; |
AlanHuchin | 0:89cf0851969b | 233 | // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both |
AlanHuchin | 0:89cf0851969b | 234 | // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate |
AlanHuchin | 0:89cf0851969b | 235 | writeByte(MPU9250_ADDRESS, CONFIG, 0x03); |
AlanHuchin | 0:89cf0851969b | 236 | |
AlanHuchin | 0:89cf0851969b | 237 | // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) |
AlanHuchin | 0:89cf0851969b | 238 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above |
AlanHuchin | 0:89cf0851969b | 239 | |
AlanHuchin | 0:89cf0851969b | 240 | // Set gyroscope full scale range |
AlanHuchin | 0:89cf0851969b | 241 | // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 |
AlanHuchin | 0:89cf0851969b | 242 | uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); // get current GYRO_CONFIG register value |
AlanHuchin | 0:89cf0851969b | 243 | // c = c & ~0xE0; // Clear self-test bits [7:5] |
AlanHuchin | 0:89cf0851969b | 244 | c = c & ~0x02; // Clear Fchoice bits [1:0] |
AlanHuchin | 0:89cf0851969b | 245 | c = c & ~0x18; // Clear AFS bits [4:3] |
AlanHuchin | 0:89cf0851969b | 246 | c = c | Gscale << 3; // Set full scale range for the gyro |
AlanHuchin | 0:89cf0851969b | 247 | // c =| 0x00; // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG |
AlanHuchin | 0:89cf0851969b | 248 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c ); // Write new GYRO_CONFIG value to register |
AlanHuchin | 0:89cf0851969b | 249 | |
AlanHuchin | 0:89cf0851969b | 250 | // Set accelerometer full-scale range configuration |
AlanHuchin | 0:89cf0851969b | 251 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); // get current ACCEL_CONFIG register value |
AlanHuchin | 0:89cf0851969b | 252 | // c = c & ~0xE0; // Clear self-test bits [7:5] |
AlanHuchin | 0:89cf0851969b | 253 | c = c & ~0x18; // Clear AFS bits [4:3] |
AlanHuchin | 0:89cf0851969b | 254 | c = c | Ascale << 3; // Set full scale range for the accelerometer |
AlanHuchin | 0:89cf0851969b | 255 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c); // Write new ACCEL_CONFIG register value |
AlanHuchin | 0:89cf0851969b | 256 | |
AlanHuchin | 0:89cf0851969b | 257 | // Set accelerometer sample rate configuration |
AlanHuchin | 0:89cf0851969b | 258 | // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for |
AlanHuchin | 0:89cf0851969b | 259 | // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz |
AlanHuchin | 0:89cf0851969b | 260 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); // get current ACCEL_CONFIG2 register value |
AlanHuchin | 0:89cf0851969b | 261 | c = c & ~0x0F; // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) |
AlanHuchin | 0:89cf0851969b | 262 | c = c | 0x03; // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz |
AlanHuchin | 0:89cf0851969b | 263 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c); // Write new ACCEL_CONFIG2 register value |
AlanHuchin | 0:89cf0851969b | 264 | |
AlanHuchin | 0:89cf0851969b | 265 | // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, |
AlanHuchin | 0:89cf0851969b | 266 | // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting |
AlanHuchin | 0:89cf0851969b | 267 | |
AlanHuchin | 0:89cf0851969b | 268 | // Configure Interrupts and Bypass Enable |
AlanHuchin | 0:89cf0851969b | 269 | // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips |
AlanHuchin | 0:89cf0851969b | 270 | // can join the I2C bus and all can be controlled by the Arduino as master |
AlanHuchin | 0:89cf0851969b | 271 | |
AlanHuchin | 0:89cf0851969b | 272 | #if USE_ISR |
AlanHuchin | 0:89cf0851969b | 273 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x12); // INT is 50 microsecond pulse and any read to clear |
AlanHuchin | 0:89cf0851969b | 274 | #else |
AlanHuchin | 0:89cf0851969b | 275 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); |
AlanHuchin | 0:89cf0851969b | 276 | #endif |
AlanHuchin | 0:89cf0851969b | 277 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt |
AlanHuchin | 0:89cf0851969b | 278 | } |
AlanHuchin | 0:89cf0851969b | 279 | |
AlanHuchin | 0:89cf0851969b | 280 | // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average |
AlanHuchin | 0:89cf0851969b | 281 | // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. |
AlanHuchin | 0:89cf0851969b | 282 | void MPU9250::calibrateMPU9250(float * dest1, float * dest2) |
AlanHuchin | 0:89cf0851969b | 283 | { |
AlanHuchin | 0:89cf0851969b | 284 | uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data |
AlanHuchin | 0:89cf0851969b | 285 | uint16_t ii, packet_count, fifo_count; |
AlanHuchin | 0:89cf0851969b | 286 | int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 287 | |
AlanHuchin | 0:89cf0851969b | 288 | // reset device, reset all registers, clear gyro and accelerometer bias registers |
AlanHuchin | 0:89cf0851969b | 289 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device |
AlanHuchin | 0:89cf0851969b | 290 | wait(0.1); |
AlanHuchin | 0:89cf0851969b | 291 | |
AlanHuchin | 0:89cf0851969b | 292 | // get stable time source |
AlanHuchin | 0:89cf0851969b | 293 | // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 |
AlanHuchin | 0:89cf0851969b | 294 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); |
AlanHuchin | 0:89cf0851969b | 295 | writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); |
AlanHuchin | 0:89cf0851969b | 296 | wait(0.2); |
AlanHuchin | 0:89cf0851969b | 297 | |
AlanHuchin | 0:89cf0851969b | 298 | // Configure device for bias calculation |
AlanHuchin | 0:89cf0851969b | 299 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts |
AlanHuchin | 0:89cf0851969b | 300 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO |
AlanHuchin | 0:89cf0851969b | 301 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source |
AlanHuchin | 0:89cf0851969b | 302 | writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master |
AlanHuchin | 0:89cf0851969b | 303 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes |
AlanHuchin | 0:89cf0851969b | 304 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP |
AlanHuchin | 0:89cf0851969b | 305 | wait(0.015); |
AlanHuchin | 0:89cf0851969b | 306 | |
AlanHuchin | 0:89cf0851969b | 307 | // Configure MPU9250 gyro and accelerometer for bias calculation |
AlanHuchin | 0:89cf0851969b | 308 | writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz |
AlanHuchin | 0:89cf0851969b | 309 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz |
AlanHuchin | 0:89cf0851969b | 310 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity |
AlanHuchin | 0:89cf0851969b | 311 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity |
AlanHuchin | 0:89cf0851969b | 312 | |
AlanHuchin | 0:89cf0851969b | 313 | uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec |
AlanHuchin | 0:89cf0851969b | 314 | uint16_t accelsensitivity = 16384; // = 16384 LSB/g |
AlanHuchin | 0:89cf0851969b | 315 | |
AlanHuchin | 0:89cf0851969b | 316 | // Configure FIFO to capture accelerometer and gyro data for bias calculation |
AlanHuchin | 0:89cf0851969b | 317 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO |
AlanHuchin | 0:89cf0851969b | 318 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) |
AlanHuchin | 0:89cf0851969b | 319 | wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes |
AlanHuchin | 0:89cf0851969b | 320 | |
AlanHuchin | 0:89cf0851969b | 321 | // At end of sample accumulation, turn off FIFO sensor read |
AlanHuchin | 0:89cf0851969b | 322 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO |
AlanHuchin | 0:89cf0851969b | 323 | readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count |
AlanHuchin | 0:89cf0851969b | 324 | fifo_count = ((uint16_t)data[0] << 8) | data[1]; |
AlanHuchin | 0:89cf0851969b | 325 | packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging |
AlanHuchin | 0:89cf0851969b | 326 | |
AlanHuchin | 0:89cf0851969b | 327 | for (ii = 0; ii < packet_count; ii++) { |
AlanHuchin | 0:89cf0851969b | 328 | int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 329 | readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging |
AlanHuchin | 0:89cf0851969b | 330 | accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO |
AlanHuchin | 0:89cf0851969b | 331 | accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; |
AlanHuchin | 0:89cf0851969b | 332 | accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; |
AlanHuchin | 0:89cf0851969b | 333 | gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; |
AlanHuchin | 0:89cf0851969b | 334 | gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; |
AlanHuchin | 0:89cf0851969b | 335 | gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; |
AlanHuchin | 0:89cf0851969b | 336 | |
AlanHuchin | 0:89cf0851969b | 337 | accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases |
AlanHuchin | 0:89cf0851969b | 338 | accel_bias[1] += (int32_t) accel_temp[1]; |
AlanHuchin | 0:89cf0851969b | 339 | accel_bias[2] += (int32_t) accel_temp[2]; |
AlanHuchin | 0:89cf0851969b | 340 | gyro_bias[0] += (int32_t) gyro_temp[0]; |
AlanHuchin | 0:89cf0851969b | 341 | gyro_bias[1] += (int32_t) gyro_temp[1]; |
AlanHuchin | 0:89cf0851969b | 342 | gyro_bias[2] += (int32_t) gyro_temp[2]; |
AlanHuchin | 0:89cf0851969b | 343 | |
AlanHuchin | 0:89cf0851969b | 344 | } |
AlanHuchin | 0:89cf0851969b | 345 | accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases |
AlanHuchin | 0:89cf0851969b | 346 | accel_bias[1] /= (int32_t) packet_count; |
AlanHuchin | 0:89cf0851969b | 347 | accel_bias[2] /= (int32_t) packet_count; |
AlanHuchin | 0:89cf0851969b | 348 | gyro_bias[0] /= (int32_t) packet_count; |
AlanHuchin | 0:89cf0851969b | 349 | gyro_bias[1] /= (int32_t) packet_count; |
AlanHuchin | 0:89cf0851969b | 350 | gyro_bias[2] /= (int32_t) packet_count; |
AlanHuchin | 0:89cf0851969b | 351 | |
AlanHuchin | 0:89cf0851969b | 352 | if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation |
AlanHuchin | 0:89cf0851969b | 353 | else {accel_bias[2] += (int32_t) accelsensitivity;} |
AlanHuchin | 0:89cf0851969b | 354 | |
AlanHuchin | 0:89cf0851969b | 355 | // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup |
AlanHuchin | 0:89cf0851969b | 356 | 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 |
AlanHuchin | 0:89cf0851969b | 357 | data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases |
AlanHuchin | 0:89cf0851969b | 358 | data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 359 | data[3] = (-gyro_bias[1]/4) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 360 | data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 361 | data[5] = (-gyro_bias[2]/4) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 362 | |
AlanHuchin | 0:89cf0851969b | 363 | /// Push gyro biases to hardware registers |
AlanHuchin | 0:89cf0851969b | 364 | /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); |
AlanHuchin | 0:89cf0851969b | 365 | writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); |
AlanHuchin | 0:89cf0851969b | 366 | writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); |
AlanHuchin | 0:89cf0851969b | 367 | writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); |
AlanHuchin | 0:89cf0851969b | 368 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); |
AlanHuchin | 0:89cf0851969b | 369 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); |
AlanHuchin | 0:89cf0851969b | 370 | */ |
AlanHuchin | 0:89cf0851969b | 371 | dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction |
AlanHuchin | 0:89cf0851969b | 372 | dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; |
AlanHuchin | 0:89cf0851969b | 373 | dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; |
AlanHuchin | 0:89cf0851969b | 374 | |
AlanHuchin | 0:89cf0851969b | 375 | // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain |
AlanHuchin | 0:89cf0851969b | 376 | // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold |
AlanHuchin | 0:89cf0851969b | 377 | // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature |
AlanHuchin | 0:89cf0851969b | 378 | // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that |
AlanHuchin | 0:89cf0851969b | 379 | // the accelerometer biases calculated above must be divided by 8. |
AlanHuchin | 0:89cf0851969b | 380 | |
AlanHuchin | 0:89cf0851969b | 381 | int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases |
AlanHuchin | 0:89cf0851969b | 382 | readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values |
AlanHuchin | 0:89cf0851969b | 383 | accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; |
AlanHuchin | 0:89cf0851969b | 384 | readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); |
AlanHuchin | 0:89cf0851969b | 385 | accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; |
AlanHuchin | 0:89cf0851969b | 386 | readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); |
AlanHuchin | 0:89cf0851969b | 387 | accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; |
AlanHuchin | 0:89cf0851969b | 388 | |
AlanHuchin | 0:89cf0851969b | 389 | uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers |
AlanHuchin | 0:89cf0851969b | 390 | uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis |
AlanHuchin | 0:89cf0851969b | 391 | |
AlanHuchin | 0:89cf0851969b | 392 | for(ii = 0; ii < 3; ii++) { |
AlanHuchin | 0:89cf0851969b | 393 | if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit |
AlanHuchin | 0:89cf0851969b | 394 | } |
AlanHuchin | 0:89cf0851969b | 395 | |
AlanHuchin | 0:89cf0851969b | 396 | // Construct total accelerometer bias, including calculated average accelerometer bias from above |
AlanHuchin | 0:89cf0851969b | 397 | accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) |
AlanHuchin | 0:89cf0851969b | 398 | accel_bias_reg[1] -= (accel_bias[1]/8); |
AlanHuchin | 0:89cf0851969b | 399 | accel_bias_reg[2] -= (accel_bias[2]/8); |
AlanHuchin | 0:89cf0851969b | 400 | |
AlanHuchin | 0:89cf0851969b | 401 | data[0] = (accel_bias_reg[0] >> 8) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 402 | data[1] = (accel_bias_reg[0]) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 403 | data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers |
AlanHuchin | 0:89cf0851969b | 404 | data[2] = (accel_bias_reg[1] >> 8) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 405 | data[3] = (accel_bias_reg[1]) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 406 | data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers |
AlanHuchin | 0:89cf0851969b | 407 | data[4] = (accel_bias_reg[2] >> 8) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 408 | data[5] = (accel_bias_reg[2]) & 0xFF; |
AlanHuchin | 0:89cf0851969b | 409 | data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers |
AlanHuchin | 0:89cf0851969b | 410 | |
AlanHuchin | 0:89cf0851969b | 411 | // Apparently this is not working for the acceleration biases in the MPU-9250 |
AlanHuchin | 0:89cf0851969b | 412 | // Are we handling the temperature correction bit properly? |
AlanHuchin | 0:89cf0851969b | 413 | // Push accelerometer biases to hardware registers |
AlanHuchin | 0:89cf0851969b | 414 | /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); |
AlanHuchin | 0:89cf0851969b | 415 | writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); |
AlanHuchin | 0:89cf0851969b | 416 | writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); |
AlanHuchin | 0:89cf0851969b | 417 | writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); |
AlanHuchin | 0:89cf0851969b | 418 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); |
AlanHuchin | 0:89cf0851969b | 419 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); |
AlanHuchin | 0:89cf0851969b | 420 | */ |
AlanHuchin | 0:89cf0851969b | 421 | // Output scaled accelerometer biases for manual subtraction in the main program |
AlanHuchin | 0:89cf0851969b | 422 | dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; |
AlanHuchin | 0:89cf0851969b | 423 | dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; |
AlanHuchin | 0:89cf0851969b | 424 | dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; |
AlanHuchin | 0:89cf0851969b | 425 | } |
AlanHuchin | 0:89cf0851969b | 426 | |
AlanHuchin | 0:89cf0851969b | 427 | void MPU9250::magcalMPU9250(float * dest1, float * dest2) |
AlanHuchin | 0:89cf0851969b | 428 | { |
AlanHuchin | 0:89cf0851969b | 429 | uint16_t ii = 0, sample_count = 0; |
AlanHuchin | 0:89cf0851969b | 430 | int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 431 | int16_t mag_max[3] = {-32767, -32767, -32767}, mag_min[3] = {32767, 32767, 32767}, mag_temp[3] = {0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 432 | |
AlanHuchin | 0:89cf0851969b | 433 | // shoot for ~fifteen seconds of mag data |
AlanHuchin | 0:89cf0851969b | 434 | if(Mmode == 0x02) sample_count = 128; // at 8 Hz ODR, new mag data is available every 125 ms |
AlanHuchin | 0:89cf0851969b | 435 | if(Mmode == 0x06) sample_count = 1500; // at 100 Hz ODR, new mag data is available every 10 ms |
AlanHuchin | 0:89cf0851969b | 436 | |
AlanHuchin | 0:89cf0851969b | 437 | for(ii = 0; ii < sample_count; ii++) { |
AlanHuchin | 0:89cf0851969b | 438 | readMagData(mag_temp); // Read the mag data |
AlanHuchin | 0:89cf0851969b | 439 | |
AlanHuchin | 0:89cf0851969b | 440 | for (int jj = 0; jj < 3; jj++) { |
AlanHuchin | 0:89cf0851969b | 441 | if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj]; |
AlanHuchin | 0:89cf0851969b | 442 | if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj]; |
AlanHuchin | 0:89cf0851969b | 443 | } |
AlanHuchin | 0:89cf0851969b | 444 | |
AlanHuchin | 0:89cf0851969b | 445 | if(Mmode == 0x02) wait(0.135); // at 8 Hz ODR, new mag data is available every 125 ms |
AlanHuchin | 0:89cf0851969b | 446 | if(Mmode == 0x06) wait(0.012); // at 100 Hz ODR, new mag data is available every 10 ms |
AlanHuchin | 0:89cf0851969b | 447 | } |
AlanHuchin | 0:89cf0851969b | 448 | |
AlanHuchin | 0:89cf0851969b | 449 | // Get hard iron correction |
AlanHuchin | 0:89cf0851969b | 450 | mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts |
AlanHuchin | 0:89cf0851969b | 451 | mag_bias[1] = (mag_max[1] + mag_min[1])/2; // get average y mag bias in counts |
AlanHuchin | 0:89cf0851969b | 452 | mag_bias[2] = (mag_max[2] + mag_min[2])/2; // get average z mag bias in counts |
AlanHuchin | 0:89cf0851969b | 453 | |
AlanHuchin | 0:89cf0851969b | 454 | dest1[0] = (float) mag_bias[0]*mRes*magCalibration[0]; // save mag biases in G for main program |
AlanHuchin | 0:89cf0851969b | 455 | dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1]; |
AlanHuchin | 0:89cf0851969b | 456 | dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2]; |
AlanHuchin | 0:89cf0851969b | 457 | |
AlanHuchin | 0:89cf0851969b | 458 | // Get soft iron correction estimate |
AlanHuchin | 0:89cf0851969b | 459 | mag_scale[0] = (mag_max[0] - mag_min[0])/2; // get average x axis max chord length in counts |
AlanHuchin | 0:89cf0851969b | 460 | mag_scale[1] = (mag_max[1] - mag_min[1])/2; // get average y axis max chord length in counts |
AlanHuchin | 0:89cf0851969b | 461 | mag_scale[2] = (mag_max[2] - mag_min[2])/2; // get average z axis max chord length in counts |
AlanHuchin | 0:89cf0851969b | 462 | |
AlanHuchin | 0:89cf0851969b | 463 | float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2]; |
AlanHuchin | 0:89cf0851969b | 464 | avg_rad /= 3.0; |
AlanHuchin | 0:89cf0851969b | 465 | |
AlanHuchin | 0:89cf0851969b | 466 | dest2[0] = avg_rad/((float)mag_scale[0]); |
AlanHuchin | 0:89cf0851969b | 467 | dest2[1] = avg_rad/((float)mag_scale[1]); |
AlanHuchin | 0:89cf0851969b | 468 | dest2[2] = avg_rad/((float)mag_scale[2]); |
AlanHuchin | 0:89cf0851969b | 469 | } |
AlanHuchin | 0:89cf0851969b | 470 | |
AlanHuchin | 0:89cf0851969b | 471 | |
AlanHuchin | 0:89cf0851969b | 472 | // Accelerometer and gyroscope self test; check calibration wrt factory settings |
AlanHuchin | 0:89cf0851969b | 473 | void MPU9250::MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass |
AlanHuchin | 0:89cf0851969b | 474 | { |
AlanHuchin | 0:89cf0851969b | 475 | uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; |
AlanHuchin | 0:89cf0851969b | 476 | uint8_t selfTest[6]; |
AlanHuchin | 0:89cf0851969b | 477 | int32_t gAvg[3] = {0}, aAvg[3] = {0}, aSTAvg[3] = {0}, gSTAvg[3] = {0}; |
AlanHuchin | 0:89cf0851969b | 478 | float factoryTrim[6]; |
AlanHuchin | 0:89cf0851969b | 479 | uint8_t FS = 0; |
AlanHuchin | 0:89cf0851969b | 480 | |
AlanHuchin | 0:89cf0851969b | 481 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz |
AlanHuchin | 0:89cf0851969b | 482 | writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz |
AlanHuchin | 0:89cf0851969b | 483 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps |
AlanHuchin | 0:89cf0851969b | 484 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz |
AlanHuchin | 0:89cf0851969b | 485 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g |
AlanHuchin | 0:89cf0851969b | 486 | |
AlanHuchin | 0:89cf0851969b | 487 | for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer |
AlanHuchin | 0:89cf0851969b | 488 | |
AlanHuchin | 0:89cf0851969b | 489 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array |
AlanHuchin | 0:89cf0851969b | 490 | aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 491 | aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 492 | aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 493 | |
AlanHuchin | 0:89cf0851969b | 494 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array |
AlanHuchin | 0:89cf0851969b | 495 | gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 496 | gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 497 | gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 498 | } |
AlanHuchin | 0:89cf0851969b | 499 | |
AlanHuchin | 0:89cf0851969b | 500 | for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings |
AlanHuchin | 0:89cf0851969b | 501 | aAvg[ii] /= 200; |
AlanHuchin | 0:89cf0851969b | 502 | gAvg[ii] /= 200; |
AlanHuchin | 0:89cf0851969b | 503 | } |
AlanHuchin | 0:89cf0851969b | 504 | |
AlanHuchin | 0:89cf0851969b | 505 | // Configure the accelerometer for self-test |
AlanHuchin | 0:89cf0851969b | 506 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g |
AlanHuchin | 0:89cf0851969b | 507 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s |
AlanHuchin | 0:89cf0851969b | 508 | wait(0.025); // Delay a while to let the device stabilize |
AlanHuchin | 0:89cf0851969b | 509 | |
AlanHuchin | 0:89cf0851969b | 510 | for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer |
AlanHuchin | 0:89cf0851969b | 511 | |
AlanHuchin | 0:89cf0851969b | 512 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array |
AlanHuchin | 0:89cf0851969b | 513 | aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 514 | aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 515 | aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 516 | |
AlanHuchin | 0:89cf0851969b | 517 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array |
AlanHuchin | 0:89cf0851969b | 518 | gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value |
AlanHuchin | 0:89cf0851969b | 519 | gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; |
AlanHuchin | 0:89cf0851969b | 520 | gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; |
AlanHuchin | 0:89cf0851969b | 521 | } |
AlanHuchin | 0:89cf0851969b | 522 | |
AlanHuchin | 0:89cf0851969b | 523 | for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings |
AlanHuchin | 0:89cf0851969b | 524 | aSTAvg[ii] /= 200; |
AlanHuchin | 0:89cf0851969b | 525 | gSTAvg[ii] /= 200; |
AlanHuchin | 0:89cf0851969b | 526 | } |
AlanHuchin | 0:89cf0851969b | 527 | |
AlanHuchin | 0:89cf0851969b | 528 | // Configure the gyro and accelerometer for normal operation |
AlanHuchin | 0:89cf0851969b | 529 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); |
AlanHuchin | 0:89cf0851969b | 530 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); |
AlanHuchin | 0:89cf0851969b | 531 | wait(0.025); // Delay a while to let the device stabilize |
AlanHuchin | 0:89cf0851969b | 532 | |
AlanHuchin | 0:89cf0851969b | 533 | // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg |
AlanHuchin | 0:89cf0851969b | 534 | selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results |
AlanHuchin | 0:89cf0851969b | 535 | selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results |
AlanHuchin | 0:89cf0851969b | 536 | selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results |
AlanHuchin | 0:89cf0851969b | 537 | selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results |
AlanHuchin | 0:89cf0851969b | 538 | selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results |
AlanHuchin | 0:89cf0851969b | 539 | selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results |
AlanHuchin | 0:89cf0851969b | 540 | |
AlanHuchin | 0:89cf0851969b | 541 | // Retrieve factory self-test value from self-test code reads |
AlanHuchin | 0:89cf0851969b | 542 | factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 543 | factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 544 | factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 545 | factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 546 | factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 547 | factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation |
AlanHuchin | 0:89cf0851969b | 548 | |
AlanHuchin | 0:89cf0851969b | 549 | // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response |
AlanHuchin | 0:89cf0851969b | 550 | // To get percent, must multiply by 100 |
AlanHuchin | 0:89cf0851969b | 551 | for (int i = 0; i < 3; i++) { |
AlanHuchin | 0:89cf0851969b | 552 | destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i] - 100.; // Report percent differences |
AlanHuchin | 0:89cf0851969b | 553 | destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3] - 100.; // Report percent differences |
AlanHuchin | 0:89cf0851969b | 554 | } |
AlanHuchin | 0:89cf0851969b | 555 | |
AlanHuchin | 0:89cf0851969b | 556 | } |
AlanHuchin | 0:89cf0851969b | 557 | |
AlanHuchin | 0:89cf0851969b | 558 | void MPU9250::MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) |
AlanHuchin | 0:89cf0851969b | 559 | { |
AlanHuchin | 0:89cf0851969b | 560 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
AlanHuchin | 0:89cf0851969b | 561 | float norm; |
AlanHuchin | 0:89cf0851969b | 562 | float hx, hy, _2bx, _2bz; |
AlanHuchin | 0:89cf0851969b | 563 | float s1, s2, s3, s4; |
AlanHuchin | 0:89cf0851969b | 564 | float qDot1, qDot2, qDot3, qDot4; |
AlanHuchin | 0:89cf0851969b | 565 | |
AlanHuchin | 0:89cf0851969b | 566 | // Auxiliary variables to avoid repeated arithmetic |
AlanHuchin | 0:89cf0851969b | 567 | float _2q1mx; |
AlanHuchin | 0:89cf0851969b | 568 | float _2q1my; |
AlanHuchin | 0:89cf0851969b | 569 | float _2q1mz; |
AlanHuchin | 0:89cf0851969b | 570 | float _2q2mx; |
AlanHuchin | 0:89cf0851969b | 571 | float _4bx; |
AlanHuchin | 0:89cf0851969b | 572 | float _4bz; |
AlanHuchin | 0:89cf0851969b | 573 | float _2q1 = 2.0f * q1; |
AlanHuchin | 0:89cf0851969b | 574 | float _2q2 = 2.0f * q2; |
AlanHuchin | 0:89cf0851969b | 575 | float _2q3 = 2.0f * q3; |
AlanHuchin | 0:89cf0851969b | 576 | float _2q4 = 2.0f * q4; |
AlanHuchin | 0:89cf0851969b | 577 | float _2q1q3 = 2.0f * q1 * q3; |
AlanHuchin | 0:89cf0851969b | 578 | float _2q3q4 = 2.0f * q3 * q4; |
AlanHuchin | 0:89cf0851969b | 579 | float q1q1 = q1 * q1; |
AlanHuchin | 0:89cf0851969b | 580 | float q1q2 = q1 * q2; |
AlanHuchin | 0:89cf0851969b | 581 | float q1q3 = q1 * q3; |
AlanHuchin | 0:89cf0851969b | 582 | float q1q4 = q1 * q4; |
AlanHuchin | 0:89cf0851969b | 583 | float q2q2 = q2 * q2; |
AlanHuchin | 0:89cf0851969b | 584 | float q2q3 = q2 * q3; |
AlanHuchin | 0:89cf0851969b | 585 | float q2q4 = q2 * q4; |
AlanHuchin | 0:89cf0851969b | 586 | float q3q3 = q3 * q3; |
AlanHuchin | 0:89cf0851969b | 587 | float q3q4 = q3 * q4; |
AlanHuchin | 0:89cf0851969b | 588 | float q4q4 = q4 * q4; |
AlanHuchin | 0:89cf0851969b | 589 | |
AlanHuchin | 0:89cf0851969b | 590 | // Normalise accelerometer measurement |
AlanHuchin | 0:89cf0851969b | 591 | norm = sqrt(ax * ax + ay * ay + az * az); |
AlanHuchin | 0:89cf0851969b | 592 | if (norm == 0.0f) return; // handle NaN |
AlanHuchin | 0:89cf0851969b | 593 | norm = 1.0f/norm; |
AlanHuchin | 0:89cf0851969b | 594 | ax *= norm; |
AlanHuchin | 0:89cf0851969b | 595 | ay *= norm; |
AlanHuchin | 0:89cf0851969b | 596 | az *= norm; |
AlanHuchin | 0:89cf0851969b | 597 | |
AlanHuchin | 0:89cf0851969b | 598 | // Normalise magnetometer measurement |
AlanHuchin | 0:89cf0851969b | 599 | norm = sqrt(mx * mx + my * my + mz * mz); |
AlanHuchin | 0:89cf0851969b | 600 | if (norm == 0.0f) return; // handle NaN |
AlanHuchin | 0:89cf0851969b | 601 | norm = 1.0f/norm; |
AlanHuchin | 0:89cf0851969b | 602 | mx *= norm; |
AlanHuchin | 0:89cf0851969b | 603 | my *= norm; |
AlanHuchin | 0:89cf0851969b | 604 | mz *= norm; |
AlanHuchin | 0:89cf0851969b | 605 | |
AlanHuchin | 0:89cf0851969b | 606 | // Reference direction of Earth's magnetic field |
AlanHuchin | 0:89cf0851969b | 607 | _2q1mx = 2.0f * q1 * mx; |
AlanHuchin | 0:89cf0851969b | 608 | _2q1my = 2.0f * q1 * my; |
AlanHuchin | 0:89cf0851969b | 609 | _2q1mz = 2.0f * q1 * mz; |
AlanHuchin | 0:89cf0851969b | 610 | _2q2mx = 2.0f * q2 * mx; |
AlanHuchin | 0:89cf0851969b | 611 | hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; |
AlanHuchin | 0:89cf0851969b | 612 | hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; |
AlanHuchin | 0:89cf0851969b | 613 | _2bx = sqrt(hx * hx + hy * hy); |
AlanHuchin | 0:89cf0851969b | 614 | _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; |
AlanHuchin | 0:89cf0851969b | 615 | _4bx = 2.0f * _2bx; |
AlanHuchin | 0:89cf0851969b | 616 | _4bz = 2.0f * _2bz; |
AlanHuchin | 0:89cf0851969b | 617 | |
AlanHuchin | 0:89cf0851969b | 618 | // Gradient decent algorithm corrective step |
AlanHuchin | 0:89cf0851969b | 619 | 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); |
AlanHuchin | 0:89cf0851969b | 620 | 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); |
AlanHuchin | 0:89cf0851969b | 621 | 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); |
AlanHuchin | 0:89cf0851969b | 622 | 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); |
AlanHuchin | 0:89cf0851969b | 623 | norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude |
AlanHuchin | 0:89cf0851969b | 624 | norm = 1.0f/norm; |
AlanHuchin | 0:89cf0851969b | 625 | s1 *= norm; |
AlanHuchin | 0:89cf0851969b | 626 | s2 *= norm; |
AlanHuchin | 0:89cf0851969b | 627 | s3 *= norm; |
AlanHuchin | 0:89cf0851969b | 628 | s4 *= norm; |
AlanHuchin | 0:89cf0851969b | 629 | |
AlanHuchin | 0:89cf0851969b | 630 | // Compute rate of change of quaternion |
AlanHuchin | 0:89cf0851969b | 631 | qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; |
AlanHuchin | 0:89cf0851969b | 632 | qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; |
AlanHuchin | 0:89cf0851969b | 633 | qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; |
AlanHuchin | 0:89cf0851969b | 634 | qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; |
AlanHuchin | 0:89cf0851969b | 635 | |
AlanHuchin | 0:89cf0851969b | 636 | // Integrate to yield quaternion |
AlanHuchin | 0:89cf0851969b | 637 | q1 += qDot1 * deltat; |
AlanHuchin | 0:89cf0851969b | 638 | q2 += qDot2 * deltat; |
AlanHuchin | 0:89cf0851969b | 639 | q3 += qDot3 * deltat; |
AlanHuchin | 0:89cf0851969b | 640 | q4 += qDot4 * deltat; |
AlanHuchin | 0:89cf0851969b | 641 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion |
AlanHuchin | 0:89cf0851969b | 642 | norm = 1.0f/norm; |
AlanHuchin | 0:89cf0851969b | 643 | q[0] = q1 * norm; |
AlanHuchin | 0:89cf0851969b | 644 | q[1] = q2 * norm; |
AlanHuchin | 0:89cf0851969b | 645 | q[2] = q3 * norm; |
AlanHuchin | 0:89cf0851969b | 646 | q[3] = q4 * norm; |
AlanHuchin | 0:89cf0851969b | 647 | |
AlanHuchin | 0:89cf0851969b | 648 | } |
AlanHuchin | 0:89cf0851969b | 649 | |
AlanHuchin | 0:89cf0851969b | 650 | // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and |
AlanHuchin | 0:89cf0851969b | 651 | // measured ones. |
AlanHuchin | 0:89cf0851969b | 652 | void MPU9250::MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) |
AlanHuchin | 0:89cf0851969b | 653 | { |
AlanHuchin | 0:89cf0851969b | 654 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability |
AlanHuchin | 0:89cf0851969b | 655 | float norm; |
AlanHuchin | 0:89cf0851969b | 656 | float hx, hy, bx, bz; |
AlanHuchin | 0:89cf0851969b | 657 | float vx, vy, vz, wx, wy, wz; |
AlanHuchin | 0:89cf0851969b | 658 | float ex, ey, ez; |
AlanHuchin | 0:89cf0851969b | 659 | float pa, pb, pc; |
AlanHuchin | 0:89cf0851969b | 660 | |
AlanHuchin | 0:89cf0851969b | 661 | // Auxiliary variables to avoid repeated arithmetic |
AlanHuchin | 0:89cf0851969b | 662 | float q1q1 = q1 * q1; |
AlanHuchin | 0:89cf0851969b | 663 | float q1q2 = q1 * q2; |
AlanHuchin | 0:89cf0851969b | 664 | float q1q3 = q1 * q3; |
AlanHuchin | 0:89cf0851969b | 665 | float q1q4 = q1 * q4; |
AlanHuchin | 0:89cf0851969b | 666 | float q2q2 = q2 * q2; |
AlanHuchin | 0:89cf0851969b | 667 | float q2q3 = q2 * q3; |
AlanHuchin | 0:89cf0851969b | 668 | float q2q4 = q2 * q4; |
AlanHuchin | 0:89cf0851969b | 669 | float q3q3 = q3 * q3; |
AlanHuchin | 0:89cf0851969b | 670 | float q3q4 = q3 * q4; |
AlanHuchin | 0:89cf0851969b | 671 | float q4q4 = q4 * q4; |
AlanHuchin | 0:89cf0851969b | 672 | |
AlanHuchin | 0:89cf0851969b | 673 | // Normalise accelerometer measurement |
AlanHuchin | 0:89cf0851969b | 674 | norm = sqrt(ax * ax + ay * ay + az * az); |
AlanHuchin | 0:89cf0851969b | 675 | if (norm == 0.0f) return; // handle NaN |
AlanHuchin | 0:89cf0851969b | 676 | norm = 1.0f / norm; // use reciprocal for division |
AlanHuchin | 0:89cf0851969b | 677 | ax *= norm; |
AlanHuchin | 0:89cf0851969b | 678 | ay *= norm; |
AlanHuchin | 0:89cf0851969b | 679 | az *= norm; |
AlanHuchin | 0:89cf0851969b | 680 | |
AlanHuchin | 0:89cf0851969b | 681 | // Normalise magnetometer measurement |
AlanHuchin | 0:89cf0851969b | 682 | norm = sqrt(mx * mx + my * my + mz * mz); |
AlanHuchin | 0:89cf0851969b | 683 | if (norm == 0.0f) return; // handle NaN |
AlanHuchin | 0:89cf0851969b | 684 | norm = 1.0f / norm; // use reciprocal for division |
AlanHuchin | 0:89cf0851969b | 685 | mx *= norm; |
AlanHuchin | 0:89cf0851969b | 686 | my *= norm; |
AlanHuchin | 0:89cf0851969b | 687 | mz *= norm; |
AlanHuchin | 0:89cf0851969b | 688 | |
AlanHuchin | 0:89cf0851969b | 689 | // Reference direction of Earth's magnetic field |
AlanHuchin | 0:89cf0851969b | 690 | hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); |
AlanHuchin | 0:89cf0851969b | 691 | hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); |
AlanHuchin | 0:89cf0851969b | 692 | bx = sqrt((hx * hx) + (hy * hy)); |
AlanHuchin | 0:89cf0851969b | 693 | bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); |
AlanHuchin | 0:89cf0851969b | 694 | |
AlanHuchin | 0:89cf0851969b | 695 | // Estimated direction of gravity and magnetic field |
AlanHuchin | 0:89cf0851969b | 696 | vx = 2.0f * (q2q4 - q1q3); |
AlanHuchin | 0:89cf0851969b | 697 | vy = 2.0f * (q1q2 + q3q4); |
AlanHuchin | 0:89cf0851969b | 698 | vz = q1q1 - q2q2 - q3q3 + q4q4; |
AlanHuchin | 0:89cf0851969b | 699 | wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); |
AlanHuchin | 0:89cf0851969b | 700 | wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); |
AlanHuchin | 0:89cf0851969b | 701 | wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); |
AlanHuchin | 0:89cf0851969b | 702 | |
AlanHuchin | 0:89cf0851969b | 703 | // Error is cross product between estimated direction and measured direction of gravity |
AlanHuchin | 0:89cf0851969b | 704 | ex = (ay * vz - az * vy) + (my * wz - mz * wy); |
AlanHuchin | 0:89cf0851969b | 705 | ey = (az * vx - ax * vz) + (mz * wx - mx * wz); |
AlanHuchin | 0:89cf0851969b | 706 | ez = (ax * vy - ay * vx) + (mx * wy - my * wx); |
AlanHuchin | 0:89cf0851969b | 707 | if (Ki > 0.0f) |
AlanHuchin | 0:89cf0851969b | 708 | { |
AlanHuchin | 0:89cf0851969b | 709 | eInt[0] += ex; // accumulate integral error |
AlanHuchin | 0:89cf0851969b | 710 | eInt[1] += ey; |
AlanHuchin | 0:89cf0851969b | 711 | eInt[2] += ez; |
AlanHuchin | 0:89cf0851969b | 712 | } |
AlanHuchin | 0:89cf0851969b | 713 | else |
AlanHuchin | 0:89cf0851969b | 714 | { |
AlanHuchin | 0:89cf0851969b | 715 | eInt[0] = 0.0f; // prevent integral wind up |
AlanHuchin | 0:89cf0851969b | 716 | eInt[1] = 0.0f; |
AlanHuchin | 0:89cf0851969b | 717 | eInt[2] = 0.0f; |
AlanHuchin | 0:89cf0851969b | 718 | } |
AlanHuchin | 0:89cf0851969b | 719 | |
AlanHuchin | 0:89cf0851969b | 720 | // Apply feedback terms |
AlanHuchin | 0:89cf0851969b | 721 | gx = gx + Kp * ex + Ki * eInt[0]; |
AlanHuchin | 0:89cf0851969b | 722 | gy = gy + Kp * ey + Ki * eInt[1]; |
AlanHuchin | 0:89cf0851969b | 723 | gz = gz + Kp * ez + Ki * eInt[2]; |
AlanHuchin | 0:89cf0851969b | 724 | |
AlanHuchin | 0:89cf0851969b | 725 | // Integrate rate of change of quaternion |
AlanHuchin | 0:89cf0851969b | 726 | pa = q2; |
AlanHuchin | 0:89cf0851969b | 727 | pb = q3; |
AlanHuchin | 0:89cf0851969b | 728 | pc = q4; |
AlanHuchin | 0:89cf0851969b | 729 | q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); |
AlanHuchin | 0:89cf0851969b | 730 | q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); |
AlanHuchin | 0:89cf0851969b | 731 | q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); |
AlanHuchin | 0:89cf0851969b | 732 | q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); |
AlanHuchin | 0:89cf0851969b | 733 | |
AlanHuchin | 0:89cf0851969b | 734 | // Normalise quaternion |
AlanHuchin | 0:89cf0851969b | 735 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); |
AlanHuchin | 0:89cf0851969b | 736 | norm = 1.0f / norm; |
AlanHuchin | 0:89cf0851969b | 737 | q[0] = q1 * norm; |
AlanHuchin | 0:89cf0851969b | 738 | q[1] = q2 * norm; |
AlanHuchin | 0:89cf0851969b | 739 | q[2] = q3 * norm; |
AlanHuchin | 0:89cf0851969b | 740 | q[3] = q4 * norm; |
AlanHuchin | 0:89cf0851969b | 741 | |
AlanHuchin | 0:89cf0851969b | 742 | } |
AlanHuchin | 0:89cf0851969b | 743 |