├── STM32F401 ├── Readme.md ├── main.cpp └── MPU9250.h ├── README.md ├── quaternionFilters.ino ├── MPU9250BasicAHRS.ino └── MPU9250BasicAHRS_t3.ino /STM32F401/Readme.md: -------------------------------------------------------------------------------- 1 | This is a translation of the Arduino sketch located in the MPU-9250 repository for the MPU-9250 9-axis motion sensor with 9 DoF sensor fusion using open-source Madgwick and Mahony algorithms and an STM32F401 M4 Cortex microprocessor. 2 | 3 | The programs were compiled using the mbed compiler and achieve sensor fusion filter update rates of 4870 Hz operating the STM32F401 at 84 MHz. 4 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | MPU-9250 2 | ======== 3 | 4 | Arduino sketch for MPU-9250 9 DoF sensor with AHRS sensor fusion 5 | 6 | Demonstrate MPU-9250 basic functionality including parameterizing the register addresses, initializing the sensor, 7 | getting properly scaled accelerometer, gyroscope, and magnetometer data out, calibration and self-test of sensors. 8 | Added display functions to allow display to on-breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. 9 | 10 | A discussion of the use and limitations of this sensor and sensor fusion in general is found ![here.] 11 | (https://github.com/kriswiner/MPU-6050/wiki/Affordable-9-DoF-Sensor-Fusion) 12 | 13 | I have also added a program to allow sensor fusion using the MPU-9250 9-axis motion sensor with the STM32F401 Nucleo board using the mbed compiler. The STM32F401 achieves a sensor fusion filter update rate using the Madgwick MARG fusion filter of 4800 Hz running the M4 Cortex ARM processor at 84 MHz; compare to the sensor fusion update rate of 2120 Hz achieved using the same filter with the Teensy 3.1 running its M4 Cortex ARM processor at 96 MHz. 14 | 15 | One reason for this difference is the single-precision floating point engine embedded in the STM32F401 core. While both ARM processors achieve impressive rates of filtering, really more than necessary for most applications, the factor of two difference translates into much lower power consumption for the same sensor fusion performance. If adequate sensor fusion filtering, say, 1000 Hz, can be achieved at much lower processor clock speed, then over all power consumption will be reduced. This really matters for wearable and other portable motion sensing and control applications. 16 | 17 | I added a version of the basic sketch that uses the i2c_t3.h 'Wire' library specifically designed for Teensy 3.1. It allows easy access to Teensy-specific capabilities such as specification of which set of hardware i2c pins will be used, the bus speed (up to 1 MHz!) and also allows master and/or slave designation to handle multiplexing between i2c devices. See www.pjrc.com/teensy and http://forum.pjrc.com/threads/21680-New-I2C-library-for-Teensy3 for details. 18 | 19 | I added another version of the sketch intended specifically for the [MPU9250_MS5637 Mini Add-On shield](https://www.tindie.com/products/onehorse/mpu9250-teensy-31-add-on-shields/) for the Teensy 3.1. 20 | 21 | ![](https://d3s5r33r268y59.cloudfront.net/44691/products/thumbs/2014-07-22T02:09:32.088Z-MPU9250micro1.png.114x76_q85_pad_rcrop.png) ![](https://d3s5r33r268y59.cloudfront.net/44691/products/thumbs/2014-07-22T02:00:54.264Z-mpu9250mini1.png.114x76_q85_pad_rcrop.png) ![](https://d3s5r33r268y59.cloudfront.net/44691/products/thumbs/2014-07-22T02:09:32.088Z-mpu9250mini2.png.114x76_q85_pad_rcrop.png) 22 | 23 | _MPU9250 + MS5637 Micro (left) and Mini (right) add-on shields, which solder onto the bottom pads 23-34 or pins 8 -17 on the [Teensy 3.1](http://store.oshpark.com/products/teensy-3-1), respectively._ 24 | 25 | It can be simply modified to work with the corresponding micro shield as well. It uses SDA/SCL on pins 17/16, respectively, and it uses the Teensy 3.1-specific Wire library i2c_t3.h. The MS5637 is a simple but high resolution pressure sensor, which can be used in its high resolution mode with power consumption of 20 microAmp, or in a lower resolution mode with power consumption of only 1 microAmp. The choice will depend on the application. The sketch calculates and outputs temperature in degrees Centigrade, pressure in millibar, and altitude in feet. In high resolution mode, the pressure is accurate to within 10 Pa or 0.1 millibar, and the height discrimination is about 13 cm. This is much better performance than achievable from the venerable MPL3115A2 and the MS5637 is in a very small package perfect for the small micro and mini add-on Teensy 3.1 shields. 26 | 27 | For a discussion of the relative merits of modern board-mounted pressure sensors, see [here](https://github.com/kriswiner/MPU-9250/wiki/Small-pressure-sensors). 28 | 29 | I added sketches for the various new Mini add-on shields for Teensy 3.1 with the MPU9250 9-axis motion sensor and either the MPL3115A2 or the newer LPS25H pressure sensor/altimeter. Now there are three flavors of 10 DoF Mini add-on boards specially designed for the Teensy 3.1 with state-of-the-art 20-bit (MPL3115A2) and 24-bit (MS5637 and LPS25H) altimeters. The LPS25H has a 32-byte FIFO and sophisticated hardware filtering which allows very low power operation while maintaining 0.01 millibar resolution. This is really quite a feat; this sensor deserves serious consideration for any airborne application you might have in mind. 30 | -------------------------------------------------------------------------------- /quaternionFilters.ino: -------------------------------------------------------------------------------- 1 | 2 | // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 3 | // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 4 | // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute 5 | // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 6 | // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 7 | // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 8 | void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 9 | { 10 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 11 | float norm; 12 | float hx, hy, _2bx, _2bz; 13 | float s1, s2, s3, s4; 14 | float qDot1, qDot2, qDot3, qDot4; 15 | 16 | // Auxiliary variables to avoid repeated arithmetic 17 | float _2q1mx; 18 | float _2q1my; 19 | float _2q1mz; 20 | float _2q2mx; 21 | float _4bx; 22 | float _4bz; 23 | float _2q1 = 2.0f * q1; 24 | float _2q2 = 2.0f * q2; 25 | float _2q3 = 2.0f * q3; 26 | float _2q4 = 2.0f * q4; 27 | float _2q1q3 = 2.0f * q1 * q3; 28 | float _2q3q4 = 2.0f * q3 * q4; 29 | float q1q1 = q1 * q1; 30 | float q1q2 = q1 * q2; 31 | float q1q3 = q1 * q3; 32 | float q1q4 = q1 * q4; 33 | float q2q2 = q2 * q2; 34 | float q2q3 = q2 * q3; 35 | float q2q4 = q2 * q4; 36 | float q3q3 = q3 * q3; 37 | float q3q4 = q3 * q4; 38 | float q4q4 = q4 * q4; 39 | 40 | // Normalise accelerometer measurement 41 | norm = sqrt(ax * ax + ay * ay + az * az); 42 | if (norm == 0.0f) return; // handle NaN 43 | norm = 1.0f/norm; 44 | ax *= norm; 45 | ay *= norm; 46 | az *= norm; 47 | 48 | // Normalise magnetometer measurement 49 | norm = sqrt(mx * mx + my * my + mz * mz); 50 | if (norm == 0.0f) return; // handle NaN 51 | norm = 1.0f/norm; 52 | mx *= norm; 53 | my *= norm; 54 | mz *= norm; 55 | 56 | // Reference direction of Earth's magnetic field 57 | _2q1mx = 2.0f * q1 * mx; 58 | _2q1my = 2.0f * q1 * my; 59 | _2q1mz = 2.0f * q1 * mz; 60 | _2q2mx = 2.0f * q2 * mx; 61 | hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; 62 | hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; 63 | _2bx = sqrt(hx * hx + hy * hy); 64 | _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; 65 | _4bx = 2.0f * _2bx; 66 | _4bz = 2.0f * _2bz; 67 | 68 | // Gradient decent algorithm corrective step 69 | 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); 70 | 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); 71 | 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); 72 | 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); 73 | norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude 74 | norm = 1.0f/norm; 75 | s1 *= norm; 76 | s2 *= norm; 77 | s3 *= norm; 78 | s4 *= norm; 79 | 80 | // Compute rate of change of quaternion 81 | qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; 82 | qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; 83 | qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; 84 | qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; 85 | 86 | // Integrate to yield quaternion 87 | q1 += qDot1 * deltat; 88 | q2 += qDot2 * deltat; 89 | q3 += qDot3 * deltat; 90 | q4 += qDot4 * deltat; 91 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 92 | norm = 1.0f/norm; 93 | q[0] = q1 * norm; 94 | q[1] = q2 * norm; 95 | q[2] = q3 * norm; 96 | q[3] = q4 * norm; 97 | 98 | } 99 | 100 | 101 | 102 | // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and 103 | // measured ones. 104 | void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) 105 | { 106 | float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 107 | float norm; 108 | float hx, hy, bx, bz; 109 | float vx, vy, vz, wx, wy, wz; 110 | float ex, ey, ez; 111 | float pa, pb, pc; 112 | 113 | // Auxiliary variables to avoid repeated arithmetic 114 | float q1q1 = q1 * q1; 115 | float q1q2 = q1 * q2; 116 | float q1q3 = q1 * q3; 117 | float q1q4 = q1 * q4; 118 | float q2q2 = q2 * q2; 119 | float q2q3 = q2 * q3; 120 | float q2q4 = q2 * q4; 121 | float q3q3 = q3 * q3; 122 | float q3q4 = q3 * q4; 123 | float q4q4 = q4 * q4; 124 | 125 | // Normalise accelerometer measurement 126 | norm = sqrt(ax * ax + ay * ay + az * az); 127 | if (norm == 0.0f) return; // handle NaN 128 | norm = 1.0f / norm; // use reciprocal for division 129 | ax *= norm; 130 | ay *= norm; 131 | az *= norm; 132 | 133 | // Normalise magnetometer measurement 134 | norm = sqrt(mx * mx + my * my + mz * mz); 135 | if (norm == 0.0f) return; // handle NaN 136 | norm = 1.0f / norm; // use reciprocal for division 137 | mx *= norm; 138 | my *= norm; 139 | mz *= norm; 140 | 141 | // Reference direction of Earth's magnetic field 142 | hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); 143 | hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); 144 | bx = sqrt((hx * hx) + (hy * hy)); 145 | bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); 146 | 147 | // Estimated direction of gravity and magnetic field 148 | vx = 2.0f * (q2q4 - q1q3); 149 | vy = 2.0f * (q1q2 + q3q4); 150 | vz = q1q1 - q2q2 - q3q3 + q4q4; 151 | wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); 152 | wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); 153 | wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); 154 | 155 | // Error is cross product between estimated direction and measured direction of gravity 156 | ex = (ay * vz - az * vy) + (my * wz - mz * wy); 157 | ey = (az * vx - ax * vz) + (mz * wx - mx * wz); 158 | ez = (ax * vy - ay * vx) + (mx * wy - my * wx); 159 | if (Ki > 0.0f) 160 | { 161 | eInt[0] += ex; // accumulate integral error 162 | eInt[1] += ey; 163 | eInt[2] += ez; 164 | } 165 | else 166 | { 167 | eInt[0] = 0.0f; // prevent integral wind up 168 | eInt[1] = 0.0f; 169 | eInt[2] = 0.0f; 170 | } 171 | 172 | // Apply feedback terms 173 | gx = gx + Kp * ex + Ki * eInt[0]; 174 | gy = gy + Kp * ey + Ki * eInt[1]; 175 | gz = gz + Kp * ez + Ki * eInt[2]; 176 | 177 | // Integrate rate of change of quaternion 178 | pa = q2; 179 | pb = q3; 180 | pc = q4; 181 | q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); 182 | q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); 183 | q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); 184 | q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); 185 | 186 | // Normalise quaternion 187 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 188 | norm = 1.0f / norm; 189 | q[0] = q1 * norm; 190 | q[1] = q2 * norm; 191 | q[2] = q3 * norm; 192 | q[3] = q4 * norm; 193 | 194 | } 195 | -------------------------------------------------------------------------------- /STM32F401/main.cpp: -------------------------------------------------------------------------------- 1 | /* MPU9250 Basic Example Code 2 | by: Kris Winer 3 | date: April 1, 2014 4 | license: Beerware - Use this code however you'd like. If you 5 | find it useful you can buy me a beer some time. 6 | 7 | Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor, 8 | getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to 9 | allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and 10 | Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. 11 | 12 | SDA and SCL should have external pull-up resistors (to 3.3V). 13 | 10k resistors are on the EMSENSR-9250 breakout board. 14 | 15 | Hardware setup: 16 | MPU9250 Breakout --------- Arduino 17 | VDD ---------------------- 3.3V 18 | VDDI --------------------- 3.3V 19 | SDA ----------------------- A4 20 | SCL ----------------------- A5 21 | GND ---------------------- GND 22 | 23 | Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library. 24 | Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. 25 | We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file. 26 | We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file. 27 | */ 28 | 29 | //#include "ST_F401_84MHZ.h" 30 | //F401_init84 myinit(0); 31 | #include "mbed.h" 32 | #include "MPU9250.h" 33 | #include "N5110.h" 34 | 35 | // Using NOKIA 5110 monochrome 84 x 48 pixel display 36 | // pin 9 - Serial clock out (SCLK) 37 | // pin 8 - Serial data out (DIN) 38 | // pin 7 - Data/Command select (D/C) 39 | // pin 5 - LCD chip select (CS) 40 | // pin 6 - LCD reset (RST) 41 | //Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6); 42 | 43 | float sum = 0; 44 | uint32_t sumCount = 0; 45 | 46 | MPU9250 mpu9250; 47 | 48 | Timer t; 49 | 50 | Serial pc(USBTX, USBRX); // tx, rx 51 | 52 | // VCC, SCE, RST, D/C, MOSI,S CLK, LED 53 | N5110 lcd(PA_8, PB_10, PA_9, PA_6, PA_7, PA_5, PC_7); 54 | 55 | 56 | 57 | int main() 58 | { 59 | pc.baud(9600); 60 | 61 | //Set up I2C 62 | i2c.frequency(400000); // use fast (400 kHz) I2C 63 | 64 | pc.printf("CPU SystemCoreClock is %d Hz\r\n", SystemCoreClock); 65 | 66 | t.start(); 67 | 68 | lcd.init(); 69 | lcd.setBrightness(0.05); 70 | 71 | 72 | // Read the WHO_AM_I register, this is a good test of communication 73 | uint8_t whoami = mpu9250.readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 74 | pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x71\n\r"); 75 | 76 | if (whoami == 0x71) // WHO_AM_I should always be 0x68 77 | { 78 | pc.printf("MPU9250 is online...\n\r"); 79 | wait(1); 80 | lcd.clear(); 81 | lcd.printString("MPU9250 OK", 0, 0); 82 | 83 | mpu9250.resetMPU9250(); // Reset registers to default in preparation for device calibration 84 | mpu9250.calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 85 | pc.printf("x gyro bias = %f\n\r", gyroBias[0]); 86 | pc.printf("y gyro bias = %f\n\r", gyroBias[1]); 87 | pc.printf("z gyro bias = %f\n\r", gyroBias[2]); 88 | pc.printf("x accel bias = %f\n\r", accelBias[0]); 89 | pc.printf("y accel bias = %f\n\r", accelBias[1]); 90 | pc.printf("z accel bias = %f\n\r", accelBias[2]); 91 | wait(2); 92 | mpu9250.initMPU9250(); 93 | pc.printf("MPU9250 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 94 | mpu9250.initAK8963(magCalibration); 95 | pc.printf("AK8963 initialized for active data mode....\n\r"); // Initialize device for active mode read of magnetometer 96 | pc.printf("Accelerometer full-scale range = %f g\n\r", 2.0f*(float)(1< 10000000.0f) { 160 | // beta = 0.04; // decrease filter gain after stabilized 161 | // zeta = 0.015; // increasey bias drift gain after stabilized 162 | // } 163 | 164 | // Pass gyro rate as rad/s 165 | mpu9250.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 166 | // mpu9250.MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 167 | 168 | // Serial print and/or display at 0.5 s rate independent of data rates 169 | delt_t = t.read_ms() - count; 170 | if (delt_t > 500) { // update LCD once per half-second independent of read rate 171 | 172 | pc.printf("ax = %f", 1000*ax); 173 | pc.printf(" ay = %f", 1000*ay); 174 | pc.printf(" az = %f mg\n\r", 1000*az); 175 | 176 | pc.printf("gx = %f", gx); 177 | pc.printf(" gy = %f", gy); 178 | pc.printf(" gz = %f deg/s\n\r", gz); 179 | 180 | pc.printf("gx = %f", mx); 181 | pc.printf(" gy = %f", my); 182 | pc.printf(" gz = %f mG\n\r", mz); 183 | 184 | tempCount = mpu9250.readTempData(); // Read the adc values 185 | temperature = ((float) tempCount) / 333.87f + 21.0f; // Temperature in degrees Centigrade 186 | pc.printf(" temperature = %f C\n\r", temperature); 187 | 188 | pc.printf("q0 = %f\n\r", q[0]); 189 | pc.printf("q1 = %f\n\r", q[1]); 190 | pc.printf("q2 = %f\n\r", q[2]); 191 | pc.printf("q3 = %f\n\r", q[3]); 192 | 193 | lcd.clear(); 194 | lcd.printString("MPU9250", 0, 0); 195 | lcd.printString("x y z", 0, 1); 196 | lcd.setXYAddress(0, 2); lcd.printChar((char)(1000*ax)); 197 | lcd.setXYAddress(20, 2); lcd.printChar((char)(1000*ay)); 198 | lcd.setXYAddress(40, 2); lcd.printChar((char)(1000*az)); lcd.printString("mg", 66, 2); 199 | 200 | 201 | // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 202 | // In this coordinate system, the positive z-axis is down toward Earth. 203 | // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 204 | // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 205 | // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 206 | // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 207 | // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 208 | // applied in the correct order which for this configuration is yaw, pitch, and then roll. 209 | // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 210 | 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]); 211 | pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 212 | 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]); 213 | pitch *= 180.0f / PI; 214 | yaw *= 180.0f / PI; 215 | yaw -= 13.8f; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 216 | roll *= 180.0f / PI; 217 | 218 | pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll); 219 | pc.printf("average rate = %f\n\r", (float) sumCount/sum); 220 | 221 | myled= !myled; 222 | count = t.read_ms(); 223 | sum = 0; 224 | sumCount = 0; 225 | } 226 | } 227 | 228 | } 229 | -------------------------------------------------------------------------------- /STM32F401/MPU9250.h: -------------------------------------------------------------------------------- 1 | #ifndef MPU9250_H 2 | #define MPU9250_H 3 | 4 | #include "mbed.h" 5 | #include "math.h" 6 | 7 | // See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in 8 | // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map 9 | // 10 | //Magnetometer Registers 11 | #define AK8963_ADDRESS 0x0C<<1 12 | #define WHO_AM_I_AK8963 0x00 // should return 0x48 13 | #define INFO 0x01 14 | #define AK8963_ST1 0x02 // data ready status bit 0 15 | #define AK8963_XOUT_L 0x03 // data 16 | #define AK8963_XOUT_H 0x04 17 | #define AK8963_YOUT_L 0x05 18 | #define AK8963_YOUT_H 0x06 19 | #define AK8963_ZOUT_L 0x07 20 | #define AK8963_ZOUT_H 0x08 21 | #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 22 | #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 23 | #define AK8963_ASTC 0x0C // Self test control 24 | #define AK8963_I2CDIS 0x0F // I2C disable 25 | #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value 26 | #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value 27 | #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value 28 | 29 | #define SELF_TEST_X_GYRO 0x00 30 | #define SELF_TEST_Y_GYRO 0x01 31 | #define SELF_TEST_Z_GYRO 0x02 32 | 33 | /*#define X_FINE_GAIN 0x03 // [7:0] fine gain 34 | #define Y_FINE_GAIN 0x04 35 | #define Z_FINE_GAIN 0x05 36 | #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 37 | #define XA_OFFSET_L_TC 0x07 38 | #define YA_OFFSET_H 0x08 39 | #define YA_OFFSET_L_TC 0x09 40 | #define ZA_OFFSET_H 0x0A 41 | #define ZA_OFFSET_L_TC 0x0B */ 42 | 43 | #define SELF_TEST_X_ACCEL 0x0D 44 | #define SELF_TEST_Y_ACCEL 0x0E 45 | #define SELF_TEST_Z_ACCEL 0x0F 46 | 47 | #define SELF_TEST_A 0x10 48 | 49 | #define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope 50 | #define XG_OFFSET_L 0x14 51 | #define YG_OFFSET_H 0x15 52 | #define YG_OFFSET_L 0x16 53 | #define ZG_OFFSET_H 0x17 54 | #define ZG_OFFSET_L 0x18 55 | #define SMPLRT_DIV 0x19 56 | #define CONFIG 0x1A 57 | #define GYRO_CONFIG 0x1B 58 | #define ACCEL_CONFIG 0x1C 59 | #define ACCEL_CONFIG2 0x1D 60 | #define LP_ACCEL_ODR 0x1E 61 | #define WOM_THR 0x1F 62 | 63 | #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms 64 | #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] 65 | #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms 66 | 67 | #define FIFO_EN 0x23 68 | #define I2C_MST_CTRL 0x24 69 | #define I2C_SLV0_ADDR 0x25 70 | #define I2C_SLV0_REG 0x26 71 | #define I2C_SLV0_CTRL 0x27 72 | #define I2C_SLV1_ADDR 0x28 73 | #define I2C_SLV1_REG 0x29 74 | #define I2C_SLV1_CTRL 0x2A 75 | #define I2C_SLV2_ADDR 0x2B 76 | #define I2C_SLV2_REG 0x2C 77 | #define I2C_SLV2_CTRL 0x2D 78 | #define I2C_SLV3_ADDR 0x2E 79 | #define I2C_SLV3_REG 0x2F 80 | #define I2C_SLV3_CTRL 0x30 81 | #define I2C_SLV4_ADDR 0x31 82 | #define I2C_SLV4_REG 0x32 83 | #define I2C_SLV4_DO 0x33 84 | #define I2C_SLV4_CTRL 0x34 85 | #define I2C_SLV4_DI 0x35 86 | #define I2C_MST_STATUS 0x36 87 | #define INT_PIN_CFG 0x37 88 | #define INT_ENABLE 0x38 89 | #define DMP_INT_STATUS 0x39 // Check DMP interrupt 90 | #define INT_STATUS 0x3A 91 | #define ACCEL_XOUT_H 0x3B 92 | #define ACCEL_XOUT_L 0x3C 93 | #define ACCEL_YOUT_H 0x3D 94 | #define ACCEL_YOUT_L 0x3E 95 | #define ACCEL_ZOUT_H 0x3F 96 | #define ACCEL_ZOUT_L 0x40 97 | #define TEMP_OUT_H 0x41 98 | #define TEMP_OUT_L 0x42 99 | #define GYRO_XOUT_H 0x43 100 | #define GYRO_XOUT_L 0x44 101 | #define GYRO_YOUT_H 0x45 102 | #define GYRO_YOUT_L 0x46 103 | #define GYRO_ZOUT_H 0x47 104 | #define GYRO_ZOUT_L 0x48 105 | #define EXT_SENS_DATA_00 0x49 106 | #define EXT_SENS_DATA_01 0x4A 107 | #define EXT_SENS_DATA_02 0x4B 108 | #define EXT_SENS_DATA_03 0x4C 109 | #define EXT_SENS_DATA_04 0x4D 110 | #define EXT_SENS_DATA_05 0x4E 111 | #define EXT_SENS_DATA_06 0x4F 112 | #define EXT_SENS_DATA_07 0x50 113 | #define EXT_SENS_DATA_08 0x51 114 | #define EXT_SENS_DATA_09 0x52 115 | #define EXT_SENS_DATA_10 0x53 116 | #define EXT_SENS_DATA_11 0x54 117 | #define EXT_SENS_DATA_12 0x55 118 | #define EXT_SENS_DATA_13 0x56 119 | #define EXT_SENS_DATA_14 0x57 120 | #define EXT_SENS_DATA_15 0x58 121 | #define EXT_SENS_DATA_16 0x59 122 | #define EXT_SENS_DATA_17 0x5A 123 | #define EXT_SENS_DATA_18 0x5B 124 | #define EXT_SENS_DATA_19 0x5C 125 | #define EXT_SENS_DATA_20 0x5D 126 | #define EXT_SENS_DATA_21 0x5E 127 | #define EXT_SENS_DATA_22 0x5F 128 | #define EXT_SENS_DATA_23 0x60 129 | #define MOT_DETECT_STATUS 0x61 130 | #define I2C_SLV0_DO 0x63 131 | #define I2C_SLV1_DO 0x64 132 | #define I2C_SLV2_DO 0x65 133 | #define I2C_SLV3_DO 0x66 134 | #define I2C_MST_DELAY_CTRL 0x67 135 | #define SIGNAL_PATH_RESET 0x68 136 | #define MOT_DETECT_CTRL 0x69 137 | #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP 138 | #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode 139 | #define PWR_MGMT_2 0x6C 140 | #define DMP_BANK 0x6D // Activates a specific bank in the DMP 141 | #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank 142 | #define DMP_REG 0x6F // Register in DMP from which to read or to which to write 143 | #define DMP_REG_1 0x70 144 | #define DMP_REG_2 0x71 145 | #define FIFO_COUNTH 0x72 146 | #define FIFO_COUNTL 0x73 147 | #define FIFO_R_W 0x74 148 | #define WHO_AM_I_MPU9250 0x75 // Should return 0x71 149 | #define XA_OFFSET_H 0x77 150 | #define XA_OFFSET_L 0x78 151 | #define YA_OFFSET_H 0x7A 152 | #define YA_OFFSET_L 0x7B 153 | #define ZA_OFFSET_H 0x7D 154 | #define ZA_OFFSET_L 0x7E 155 | 156 | // Using the MSENSR-9250 breakout board, ADO is set to 0 157 | // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 158 | //mbed uses the eight-bit device address, so shift seven-bit addresses left by one! 159 | #define ADO 0 160 | #if ADO 161 | #define MPU9250_ADDRESS 0x69<<1 // Device address when ADO = 1 162 | #else 163 | #define MPU9250_ADDRESS 0x68<<1 // Device address when ADO = 0 164 | #endif 165 | 166 | // Set initial input parameters 167 | enum Ascale { 168 | AFS_2G = 0, 169 | AFS_4G, 170 | AFS_8G, 171 | AFS_16G 172 | }; 173 | 174 | enum Gscale { 175 | GFS_250DPS = 0, 176 | GFS_500DPS, 177 | GFS_1000DPS, 178 | GFS_2000DPS 179 | }; 180 | 181 | enum Mscale { 182 | MFS_14BITS = 0, // 0.6 mG per LSB 183 | MFS_16BITS // 0.15 mG per LSB 184 | }; 185 | 186 | uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G 187 | uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS 188 | uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution 189 | uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR 190 | float aRes, gRes, mRes; // scale resolutions per LSB for the sensors 191 | 192 | //Set up I2C, (SDA,SCL) 193 | I2C i2c(I2C_SDA, I2C_SCL); 194 | 195 | DigitalOut myled(LED1); 196 | 197 | // Pin definitions 198 | int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 199 | 200 | int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 201 | int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 202 | int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output 203 | float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias 204 | float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 205 | float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 206 | int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 207 | float temperature; 208 | float SelfTest[6]; 209 | 210 | int delt_t = 0; // used to control display output rate 211 | int count = 0; // used to control display output rate 212 | 213 | // parameters for 6 DoF sensor fusion calculations 214 | float PI = 3.14159265358979323846f; 215 | 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 216 | float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 217 | float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 218 | 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 219 | #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 220 | #define Ki 0.0f 221 | 222 | float pitch, yaw, roll; 223 | float deltat = 0.0f; // integration interval for both filter schemes 224 | int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 225 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 226 | float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 227 | 228 | class MPU9250 { 229 | 230 | protected: 231 | 232 | public: 233 | //=================================================================================================================== 234 | //====== Set of useful function to access acceleratio, gyroscope, and temperature data 235 | //=================================================================================================================== 236 | 237 | void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 238 | { 239 | char data_write[2]; 240 | data_write[0] = subAddress; 241 | data_write[1] = data; 242 | i2c.write(address, data_write, 2, 0); 243 | } 244 | 245 | char readByte(uint8_t address, uint8_t subAddress) 246 | { 247 | char data[1]; // `data` will store the register data 248 | char data_write[1]; 249 | data_write[0] = subAddress; 250 | i2c.write(address, data_write, 1, 1); // no stop 251 | i2c.read(address, data, 1, 0); 252 | return data[0]; 253 | } 254 | 255 | void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 256 | { 257 | char data[14]; 258 | char data_write[1]; 259 | data_write[0] = subAddress; 260 | i2c.write(address, data_write, 1, 1); // no stop 261 | i2c.read(address, data, count, 0); 262 | for(int ii = 0; ii < count; ii++) { 263 | dest[ii] = data[ii]; 264 | } 265 | } 266 | 267 | 268 | void getMres() { 269 | switch (Mscale) 270 | { 271 | // Possible magnetometer scales (and their register bit settings) are: 272 | // 14 bit resolution (0) and 16 bit resolution (1) 273 | case MFS_14BITS: 274 | mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss 275 | break; 276 | case MFS_16BITS: 277 | mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss 278 | break; 279 | } 280 | } 281 | 282 | 283 | void getGres() { 284 | switch (Gscale) 285 | { 286 | // Possible gyro scales (and their register bit settings) are: 287 | // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 288 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 289 | case GFS_250DPS: 290 | gRes = 250.0/32768.0; 291 | break; 292 | case GFS_500DPS: 293 | gRes = 500.0/32768.0; 294 | break; 295 | case GFS_1000DPS: 296 | gRes = 1000.0/32768.0; 297 | break; 298 | case GFS_2000DPS: 299 | gRes = 2000.0/32768.0; 300 | break; 301 | } 302 | } 303 | 304 | 305 | void getAres() { 306 | switch (Ascale) 307 | { 308 | // Possible accelerometer scales (and their register bit settings) are: 309 | // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 310 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 311 | case AFS_2G: 312 | aRes = 2.0/32768.0; 313 | break; 314 | case AFS_4G: 315 | aRes = 4.0/32768.0; 316 | break; 317 | case AFS_8G: 318 | aRes = 8.0/32768.0; 319 | break; 320 | case AFS_16G: 321 | aRes = 16.0/32768.0; 322 | break; 323 | } 324 | } 325 | 326 | 327 | void readAccelData(int16_t * destination) 328 | { 329 | uint8_t rawData[6]; // x/y/z accel register data stored here 330 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 331 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 332 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 333 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 334 | } 335 | 336 | void readGyroData(int16_t * destination) 337 | { 338 | uint8_t rawData[6]; // x/y/z gyro register data stored here 339 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 340 | destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 341 | destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 342 | destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 343 | } 344 | 345 | void readMagData(int16_t * destination) 346 | { 347 | uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 348 | if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 349 | readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 350 | uint8_t c = rawData[6]; // End data read by reading ST2 register 351 | if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data 352 | destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value 353 | destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian 354 | destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ; 355 | } 356 | } 357 | } 358 | 359 | int16_t readTempData() 360 | { 361 | uint8_t rawData[2]; // x/y/z gyro register data stored here 362 | readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 363 | return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 364 | } 365 | 366 | 367 | void resetMPU9250() { 368 | // reset device 369 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 370 | wait(0.1); 371 | } 372 | 373 | void initAK8963(float * destination) 374 | { 375 | // First extract the factory calibration for each magnetometer axis 376 | uint8_t rawData[3]; // x/y/z gyro calibration data stored here 377 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 378 | wait(0.01); 379 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 380 | wait(0.01); 381 | readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 382 | destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc. 383 | destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; 384 | destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; 385 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 386 | wait(0.01); 387 | // Configure the magnetometer for continuous read and highest resolution 388 | // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 389 | // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 390 | writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 391 | wait(0.01); 392 | } 393 | 394 | 395 | void initMPU9250() 396 | { 397 | // Initialize MPU9250 device 398 | // wake up device 399 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 400 | wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 401 | 402 | // get stable time source 403 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 404 | 405 | // Configure Gyro and Accelerometer 406 | // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 407 | // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 408 | // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 409 | writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 410 | 411 | // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 412 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 413 | 414 | // Set gyroscope full scale range 415 | // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 416 | uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 417 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 418 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 419 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 420 | 421 | // Set accelerometer configuration 422 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 423 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 424 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 425 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 426 | 427 | // Set accelerometer sample rate configuration 428 | // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 429 | // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 430 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 431 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 432 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 433 | 434 | // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 435 | // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 436 | 437 | // Configure Interrupts and Bypass Enable 438 | // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 439 | // can join the I2C bus and all can be controlled by the Arduino as master 440 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 441 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 442 | } 443 | 444 | // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 445 | // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 446 | void calibrateMPU9250(float * dest1, float * dest2) 447 | { 448 | uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 449 | uint16_t ii, packet_count, fifo_count; 450 | int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 451 | 452 | // reset device, reset all registers, clear gyro and accelerometer bias registers 453 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 454 | wait(0.1); 455 | 456 | // get stable time source 457 | // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 458 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 459 | writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 460 | wait(0.2); 461 | 462 | // Configure device for bias calculation 463 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 464 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 465 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 466 | writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 467 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 468 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 469 | wait(0.015); 470 | 471 | // Configure MPU9250 gyro and accelerometer for bias calculation 472 | writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 473 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 474 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 475 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 476 | 477 | uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 478 | uint16_t accelsensitivity = 16384; // = 16384 LSB/g 479 | 480 | // Configure FIFO to capture accelerometer and gyro data for bias calculation 481 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 482 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250) 483 | wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes 484 | 485 | // At end of sample accumulation, turn off FIFO sensor read 486 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 487 | readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 488 | fifo_count = ((uint16_t)data[0] << 8) | data[1]; 489 | packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 490 | 491 | for (ii = 0; ii < packet_count; ii++) { 492 | int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 493 | readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 494 | accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 495 | accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 496 | accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 497 | gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 498 | gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 499 | gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 500 | 501 | accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 502 | accel_bias[1] += (int32_t) accel_temp[1]; 503 | accel_bias[2] += (int32_t) accel_temp[2]; 504 | gyro_bias[0] += (int32_t) gyro_temp[0]; 505 | gyro_bias[1] += (int32_t) gyro_temp[1]; 506 | gyro_bias[2] += (int32_t) gyro_temp[2]; 507 | 508 | } 509 | accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 510 | accel_bias[1] /= (int32_t) packet_count; 511 | accel_bias[2] /= (int32_t) packet_count; 512 | gyro_bias[0] /= (int32_t) packet_count; 513 | gyro_bias[1] /= (int32_t) packet_count; 514 | gyro_bias[2] /= (int32_t) packet_count; 515 | 516 | if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 517 | else {accel_bias[2] += (int32_t) accelsensitivity;} 518 | 519 | // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 520 | 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 521 | data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 522 | data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 523 | data[3] = (-gyro_bias[1]/4) & 0xFF; 524 | data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 525 | data[5] = (-gyro_bias[2]/4) & 0xFF; 526 | 527 | /// Push gyro biases to hardware registers 528 | /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 529 | writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 530 | writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 531 | writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 532 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 533 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 534 | */ 535 | dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 536 | dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 537 | dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 538 | 539 | // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 540 | // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 541 | // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 542 | // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 543 | // the accelerometer biases calculated above must be divided by 8. 544 | 545 | int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 546 | readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 547 | accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 548 | readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 549 | accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 550 | readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 551 | accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 552 | 553 | uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 554 | uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 555 | 556 | for(ii = 0; ii < 3; ii++) { 557 | if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 558 | } 559 | 560 | // Construct total accelerometer bias, including calculated average accelerometer bias from above 561 | accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 562 | accel_bias_reg[1] -= (accel_bias[1]/8); 563 | accel_bias_reg[2] -= (accel_bias[2]/8); 564 | 565 | data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 566 | data[1] = (accel_bias_reg[0]) & 0xFF; 567 | data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 568 | data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 569 | data[3] = (accel_bias_reg[1]) & 0xFF; 570 | data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 571 | data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 572 | data[5] = (accel_bias_reg[2]) & 0xFF; 573 | data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 574 | 575 | // Apparently this is not working for the acceleration biases in the MPU-9250 576 | // Are we handling the temperature correction bit properly? 577 | // Push accelerometer biases to hardware registers 578 | /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 579 | writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 580 | writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 581 | writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 582 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 583 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 584 | */ 585 | // Output scaled accelerometer biases for manual subtraction in the main program 586 | dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 587 | dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 588 | dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 589 | } 590 | 591 | 592 | // Accelerometer and gyroscope self test; check calibration wrt factory settings 593 | void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 594 | { 595 | uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 596 | uint8_t selfTest[6]; 597 | int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 598 | float factoryTrim[6]; 599 | uint8_t FS = 0; 600 | 601 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 602 | writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 603 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1< 0.0f) 838 | { 839 | eInt[0] += ex; // accumulate integral error 840 | eInt[1] += ey; 841 | eInt[2] += ez; 842 | } 843 | else 844 | { 845 | eInt[0] = 0.0f; // prevent integral wind up 846 | eInt[1] = 0.0f; 847 | eInt[2] = 0.0f; 848 | } 849 | 850 | // Apply feedback terms 851 | gx = gx + Kp * ex + Ki * eInt[0]; 852 | gy = gy + Kp * ey + Ki * eInt[1]; 853 | gz = gz + Kp * ez + Ki * eInt[2]; 854 | 855 | // Integrate rate of change of quaternion 856 | pa = q2; 857 | pb = q3; 858 | pc = q4; 859 | q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); 860 | q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); 861 | q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); 862 | q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); 863 | 864 | // Normalise quaternion 865 | norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); 866 | norm = 1.0f / norm; 867 | q[0] = q1 * norm; 868 | q[1] = q2 * norm; 869 | q[2] = q3 * norm; 870 | q[3] = q4 * norm; 871 | 872 | } 873 | }; 874 | #endif 875 | -------------------------------------------------------------------------------- /MPU9250BasicAHRS.ino: -------------------------------------------------------------------------------- 1 | /* MPU9250 Basic Example Code 2 | by: Kris Winer 3 | date: April 1, 2014 4 | license: Beerware - Use this code however you'd like. If you 5 | find it useful you can buy me a beer some time. 6 | 7 | Demonstrate basic MPU-9250 functionality including parameterizing the register addresses, initializing the sensor, 8 | getting properly scaled accelerometer, gyroscope, and magnetometer data out. Added display functions to 9 | allow display to on breadboard monitor. Addition of 9 DoF sensor fusion using open source Madgwick and 10 | Mahony filter algorithms. Sketch runs on the 3.3 V 8 MHz Pro Mini and the Teensy 3.1. 11 | 12 | SDA and SCL should have external pull-up resistors (to 3.3V). 13 | 10k resistors are on the EMSENSR-9250 breakout board. 14 | 15 | Hardware setup: 16 | MPU9250 Breakout --------- Arduino 17 | VDD ---------------------- 3.3V 18 | VDDI --------------------- 3.3V 19 | SDA ----------------------- A4 20 | SCL ----------------------- A5 21 | GND ---------------------- GND 22 | 23 | Note: The MPU9250 is an I2C sensor and uses the Arduino Wire library. 24 | Because the sensor is not 5V tolerant, we are using a 3.3 V 8 MHz Pro Mini or a 3.3 V Teensy 3.1. 25 | We have disabled the internal pull-ups used by the Wire library in the Wire.h/twi.c utility file. 26 | We are also using the 400 kHz fast I2C mode by setting the TWI_FREQ to 400000L /twi.h utility file. 27 | */ 28 | #include 29 | #include 30 | #include 31 | #include 32 | 33 | // Using NOKIA 5110 monochrome 84 x 48 pixel display 34 | // pin 9 - Serial clock out (SCLK) 35 | // pin 8 - Serial data out (DIN) 36 | // pin 7 - Data/Command select (D/C) 37 | // pin 5 - LCD chip select (CS) 38 | // pin 6 - LCD reset (RST) 39 | Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6); 40 | 41 | // See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in 42 | // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map 43 | // 44 | //Magnetometer Registers 45 | #define AK8963_ADDRESS 0x0C 46 | #define WHO_AM_I_AK8963 0x00 // should return 0x48 47 | #define INFO 0x01 48 | #define AK8963_ST1 0x02 // data ready status bit 0 49 | #define AK8963_XOUT_L 0x03 // data 50 | #define AK8963_XOUT_H 0x04 51 | #define AK8963_YOUT_L 0x05 52 | #define AK8963_YOUT_H 0x06 53 | #define AK8963_ZOUT_L 0x07 54 | #define AK8963_ZOUT_H 0x08 55 | #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 56 | #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 57 | #define AK8963_ASTC 0x0C // Self test control 58 | #define AK8963_I2CDIS 0x0F // I2C disable 59 | #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value 60 | #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value 61 | #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value 62 | 63 | #define SELF_TEST_X_GYRO 0x00 64 | #define SELF_TEST_Y_GYRO 0x01 65 | #define SELF_TEST_Z_GYRO 0x02 66 | 67 | /*#define X_FINE_GAIN 0x03 // [7:0] fine gain 68 | #define Y_FINE_GAIN 0x04 69 | #define Z_FINE_GAIN 0x05 70 | #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 71 | #define XA_OFFSET_L_TC 0x07 72 | #define YA_OFFSET_H 0x08 73 | #define YA_OFFSET_L_TC 0x09 74 | #define ZA_OFFSET_H 0x0A 75 | #define ZA_OFFSET_L_TC 0x0B */ 76 | 77 | #define SELF_TEST_X_ACCEL 0x0D 78 | #define SELF_TEST_Y_ACCEL 0x0E 79 | #define SELF_TEST_Z_ACCEL 0x0F 80 | 81 | #define SELF_TEST_A 0x10 82 | 83 | #define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope 84 | #define XG_OFFSET_L 0x14 85 | #define YG_OFFSET_H 0x15 86 | #define YG_OFFSET_L 0x16 87 | #define ZG_OFFSET_H 0x17 88 | #define ZG_OFFSET_L 0x18 89 | #define SMPLRT_DIV 0x19 90 | #define CONFIG 0x1A 91 | #define GYRO_CONFIG 0x1B 92 | #define ACCEL_CONFIG 0x1C 93 | #define ACCEL_CONFIG2 0x1D 94 | #define LP_ACCEL_ODR 0x1E 95 | #define WOM_THR 0x1F 96 | 97 | #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms 98 | #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] 99 | #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms 100 | 101 | #define FIFO_EN 0x23 102 | #define I2C_MST_CTRL 0x24 103 | #define I2C_SLV0_ADDR 0x25 104 | #define I2C_SLV0_REG 0x26 105 | #define I2C_SLV0_CTRL 0x27 106 | #define I2C_SLV1_ADDR 0x28 107 | #define I2C_SLV1_REG 0x29 108 | #define I2C_SLV1_CTRL 0x2A 109 | #define I2C_SLV2_ADDR 0x2B 110 | #define I2C_SLV2_REG 0x2C 111 | #define I2C_SLV2_CTRL 0x2D 112 | #define I2C_SLV3_ADDR 0x2E 113 | #define I2C_SLV3_REG 0x2F 114 | #define I2C_SLV3_CTRL 0x30 115 | #define I2C_SLV4_ADDR 0x31 116 | #define I2C_SLV4_REG 0x32 117 | #define I2C_SLV4_DO 0x33 118 | #define I2C_SLV4_CTRL 0x34 119 | #define I2C_SLV4_DI 0x35 120 | #define I2C_MST_STATUS 0x36 121 | #define INT_PIN_CFG 0x37 122 | #define INT_ENABLE 0x38 123 | #define DMP_INT_STATUS 0x39 // Check DMP interrupt 124 | #define INT_STATUS 0x3A 125 | #define ACCEL_XOUT_H 0x3B 126 | #define ACCEL_XOUT_L 0x3C 127 | #define ACCEL_YOUT_H 0x3D 128 | #define ACCEL_YOUT_L 0x3E 129 | #define ACCEL_ZOUT_H 0x3F 130 | #define ACCEL_ZOUT_L 0x40 131 | #define TEMP_OUT_H 0x41 132 | #define TEMP_OUT_L 0x42 133 | #define GYRO_XOUT_H 0x43 134 | #define GYRO_XOUT_L 0x44 135 | #define GYRO_YOUT_H 0x45 136 | #define GYRO_YOUT_L 0x46 137 | #define GYRO_ZOUT_H 0x47 138 | #define GYRO_ZOUT_L 0x48 139 | #define EXT_SENS_DATA_00 0x49 140 | #define EXT_SENS_DATA_01 0x4A 141 | #define EXT_SENS_DATA_02 0x4B 142 | #define EXT_SENS_DATA_03 0x4C 143 | #define EXT_SENS_DATA_04 0x4D 144 | #define EXT_SENS_DATA_05 0x4E 145 | #define EXT_SENS_DATA_06 0x4F 146 | #define EXT_SENS_DATA_07 0x50 147 | #define EXT_SENS_DATA_08 0x51 148 | #define EXT_SENS_DATA_09 0x52 149 | #define EXT_SENS_DATA_10 0x53 150 | #define EXT_SENS_DATA_11 0x54 151 | #define EXT_SENS_DATA_12 0x55 152 | #define EXT_SENS_DATA_13 0x56 153 | #define EXT_SENS_DATA_14 0x57 154 | #define EXT_SENS_DATA_15 0x58 155 | #define EXT_SENS_DATA_16 0x59 156 | #define EXT_SENS_DATA_17 0x5A 157 | #define EXT_SENS_DATA_18 0x5B 158 | #define EXT_SENS_DATA_19 0x5C 159 | #define EXT_SENS_DATA_20 0x5D 160 | #define EXT_SENS_DATA_21 0x5E 161 | #define EXT_SENS_DATA_22 0x5F 162 | #define EXT_SENS_DATA_23 0x60 163 | #define MOT_DETECT_STATUS 0x61 164 | #define I2C_SLV0_DO 0x63 165 | #define I2C_SLV1_DO 0x64 166 | #define I2C_SLV2_DO 0x65 167 | #define I2C_SLV3_DO 0x66 168 | #define I2C_MST_DELAY_CTRL 0x67 169 | #define SIGNAL_PATH_RESET 0x68 170 | #define MOT_DETECT_CTRL 0x69 171 | #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP 172 | #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode 173 | #define PWR_MGMT_2 0x6C 174 | #define DMP_BANK 0x6D // Activates a specific bank in the DMP 175 | #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank 176 | #define DMP_REG 0x6F // Register in DMP from which to read or to which to write 177 | #define DMP_REG_1 0x70 178 | #define DMP_REG_2 0x71 179 | #define FIFO_COUNTH 0x72 180 | #define FIFO_COUNTL 0x73 181 | #define FIFO_R_W 0x74 182 | #define WHO_AM_I_MPU9250 0x75 // Should return 0x71 183 | #define XA_OFFSET_H 0x77 184 | #define XA_OFFSET_L 0x78 185 | #define YA_OFFSET_H 0x7A 186 | #define YA_OFFSET_L 0x7B 187 | #define ZA_OFFSET_H 0x7D 188 | #define ZA_OFFSET_L 0x7E 189 | 190 | // Using the MSENSR-9250 breakout board, ADO is set to 0 191 | // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 192 | #define ADO 1 193 | #if ADO 194 | #define MPU9250_ADDRESS 0x69 // Device address when ADO = 1 195 | #else 196 | #define MPU9250_ADDRESS 0x68 // Device address when ADO = 0 197 | #define AK8963_ADDRESS 0x0C // Address of magnetometer 198 | #endif 199 | 200 | #define AHRS true // set to false for basic data read 201 | #define SerialDebug true // set to true to get Serial output for debugging 202 | 203 | // Set initial input parameters 204 | enum Ascale { 205 | AFS_2G = 0, 206 | AFS_4G, 207 | AFS_8G, 208 | AFS_16G 209 | }; 210 | 211 | enum Gscale { 212 | GFS_250DPS = 0, 213 | GFS_500DPS, 214 | GFS_1000DPS, 215 | GFS_2000DPS 216 | }; 217 | 218 | enum Mscale { 219 | MFS_14BITS = 0, // 0.6 mG per LSB 220 | MFS_16BITS // 0.15 mG per LSB 221 | }; 222 | 223 | // Specify sensor full scale 224 | uint8_t Gscale = GFS_250DPS; 225 | uint8_t Ascale = AFS_2G; 226 | uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution 227 | uint8_t Mmode = 0x02; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read 228 | float aRes, gRes, mRes; // scale resolutions per LSB for the sensors 229 | 230 | // Pin definitions 231 | int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 232 | int myLed = 13; // Set up pin 13 led for toggling 233 | 234 | int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 235 | int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 236 | int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output 237 | float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias 238 | float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 239 | int16_t tempCount; // temperature raw count output 240 | float temperature; // Stores the real internal chip temperature in degrees Celsius 241 | float SelfTest[6]; // holds results of gyro and accelerometer self test 242 | 243 | // global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) 244 | float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) 245 | float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 246 | // There is a tradeoff in the beta parameter between accuracy and response speed. 247 | // In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. 248 | // However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. 249 | // Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! 250 | // By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec 251 | // I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; 252 | // the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. 253 | // In any case, this is the free parameter in the Madgwick filtering and fusion scheme. 254 | float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 255 | 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 256 | #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 257 | #define Ki 0.0f 258 | 259 | uint32_t delt_t = 0; // used to control display output rate 260 | uint32_t count = 0, sumCount = 0; // used to control display output rate 261 | float pitch, yaw, roll; 262 | float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes 263 | uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval 264 | uint32_t Now = 0; // used to calculate integration interval 265 | 266 | float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 267 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 268 | float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 269 | 270 | 271 | void setup() 272 | { 273 | Wire.begin(); 274 | // TWBR = 12; // 400 kbit/sec I2C speed 275 | Serial.begin(38400); 276 | 277 | // Set up the interrupt pin, its set as active high, push-pull 278 | pinMode(intPin, INPUT); 279 | digitalWrite(intPin, LOW); 280 | pinMode(myLed, OUTPUT); 281 | digitalWrite(myLed, HIGH); 282 | 283 | display.begin(); // Ini8ialize the display 284 | display.setContrast(58); // Set the contrast 285 | 286 | // Start device display with ID of sensor 287 | display.clearDisplay(); 288 | display.setTextSize(2); 289 | display.setCursor(0,0); display.print("MPU9250"); 290 | display.setTextSize(1); 291 | display.setCursor(0, 20); display.print("9-DOF 16-bit"); 292 | display.setCursor(0, 30); display.print("motion sensor"); 293 | display.setCursor(20,40); display.print("60 ug LSB"); 294 | display.display(); 295 | delay(1000); 296 | 297 | // Set up for data display 298 | display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. 299 | display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen 300 | display.clearDisplay(); // clears the screen and buffer 301 | 302 | // Read the WHO_AM_I register, this is a good test of communication 303 | byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 304 | Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); 305 | display.setCursor(20,0); display.print("MPU9250"); 306 | display.setCursor(0,10); display.print("I AM"); 307 | display.setCursor(0,20); display.print(c, HEX); 308 | display.setCursor(0,30); display.print("I Should Be"); 309 | display.setCursor(0,40); display.print(0x71, HEX); 310 | display.display(); 311 | delay(1000); 312 | 313 | if (c == 0x71) // WHO_AM_I should always be 0x68 314 | { 315 | Serial.println("MPU9250 is online..."); 316 | 317 | MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values 318 | Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); 319 | Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); 320 | Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); 321 | Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); 322 | Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); 323 | Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); 324 | 325 | calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 326 | display.clearDisplay(); 327 | 328 | display.setCursor(0, 0); display.print("MPU9250 bias"); 329 | display.setCursor(0, 8); display.print(" x y z "); 330 | 331 | display.setCursor(0, 16); display.print((int)(1000*accelBias[0])); 332 | display.setCursor(24, 16); display.print((int)(1000*accelBias[1])); 333 | display.setCursor(48, 16); display.print((int)(1000*accelBias[2])); 334 | display.setCursor(72, 16); display.print("mg"); 335 | 336 | display.setCursor(0, 24); display.print(gyroBias[0], 1); 337 | display.setCursor(24, 24); display.print(gyroBias[1], 1); 338 | display.setCursor(48, 24); display.print(gyroBias[2], 1); 339 | display.setCursor(66, 24); display.print("o/s"); 340 | 341 | display.display(); 342 | delay(1000); 343 | 344 | initMPU9250(); 345 | Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 346 | 347 | // Read the WHO_AM_I register of the magnetometer, this is a good test of communication 348 | byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 349 | Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); 350 | display.clearDisplay(); 351 | display.setCursor(20,0); display.print("AK8963"); 352 | display.setCursor(0,10); display.print("I AM"); 353 | display.setCursor(0,20); display.print(d, HEX); 354 | display.setCursor(0,30); display.print("I Should Be"); 355 | display.setCursor(0,40); display.print(0x48, HEX); 356 | display.display(); 357 | delay(1000); 358 | 359 | // Get magnetometer calibration from AK8963 ROM 360 | initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer 361 | 362 | if(SerialDebug) { 363 | // Serial.println("Calibration values: "); 364 | Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); 365 | Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); 366 | Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); 367 | } 368 | 369 | display.clearDisplay(); 370 | display.setCursor(20,0); display.print("AK8963"); 371 | display.setCursor(0,10); display.print("ASAX "); display.setCursor(50,10); display.print(magCalibration[0], 2); 372 | display.setCursor(0,20); display.print("ASAY "); display.setCursor(50,20); display.print(magCalibration[1], 2); 373 | display.setCursor(0,30); display.print("ASAZ "); display.setCursor(50,30); display.print(magCalibration[2], 2); 374 | display.display(); 375 | delay(1000); 376 | } 377 | else 378 | { 379 | Serial.print("Could not connect to MPU9250: 0x"); 380 | Serial.println(c, HEX); 381 | while(1) ; // Loop forever if communication doesn't happen 382 | } 383 | } 384 | 385 | void loop() 386 | { 387 | // If intPin goes high, all data registers have new data 388 | if (readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 389 | readAccelData(accelCount); // Read the x/y/z adc values 390 | getAres(); 391 | 392 | // Now we'll calculate the accleration value into actual g's 393 | ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set 394 | ay = (float)accelCount[1]*aRes; // - accelBias[1]; 395 | az = (float)accelCount[2]*aRes; // - accelBias[2]; 396 | 397 | readGyroData(gyroCount); // Read the x/y/z adc values 398 | getGres(); 399 | 400 | // Calculate the gyro value into actual degrees per second 401 | gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set 402 | gy = (float)gyroCount[1]*gRes; 403 | gz = (float)gyroCount[2]*gRes; 404 | 405 | readMagData(magCount); // Read the x/y/z adc values 406 | getMres(); 407 | magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated 408 | magbias[1] = +120.; // User environmental x-axis correction in milliGauss 409 | magbias[2] = +125.; // User environmental x-axis correction in milliGauss 410 | 411 | // Calculate the magnetometer values in milliGauss 412 | // Include factory calibration per data sheet and user environmental corrections 413 | mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set 414 | my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 415 | mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 416 | } 417 | 418 | Now = micros(); 419 | deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update 420 | lastUpdate = Now; 421 | 422 | sum += deltat; // sum for averaging filter update rate 423 | sumCount++; 424 | 425 | // Sensors x (y)-axis of the accelerometer is aligned with the y (x)-axis of the magnetometer; 426 | // the magnetometer z-axis (+ down) is opposite to z-axis (+ up) of accelerometer and gyro! 427 | // We have to make some allowance for this orientationmismatch in feeding the output to the quaternion filter. 428 | // For the MPU-9250, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like 429 | // in the LSM9DS0 sensor. This rotation can be modified to allow any convenient orientation convention. 430 | // This is ok by aircraft orientation standards! 431 | // Pass gyro rate as rad/s 432 | // MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 433 | MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 434 | 435 | 436 | if (!AHRS) { 437 | delt_t = millis() - count; 438 | if(delt_t > 500) { 439 | 440 | if(SerialDebug) { 441 | // Print acceleration values in milligs! 442 | Serial.print("X-acceleration: "); Serial.print(1000*ax); Serial.print(" mg "); 443 | Serial.print("Y-acceleration: "); Serial.print(1000*ay); Serial.print(" mg "); 444 | Serial.print("Z-acceleration: "); Serial.print(1000*az); Serial.println(" mg "); 445 | 446 | // Print gyro values in degree/sec 447 | Serial.print("X-gyro rate: "); Serial.print(gx, 3); Serial.print(" degrees/sec "); 448 | Serial.print("Y-gyro rate: "); Serial.print(gy, 3); Serial.print(" degrees/sec "); 449 | Serial.print("Z-gyro rate: "); Serial.print(gz, 3); Serial.println(" degrees/sec"); 450 | 451 | // Print mag values in degree/sec 452 | Serial.print("X-mag field: "); Serial.print(mx); Serial.print(" mG "); 453 | Serial.print("Y-mag field: "); Serial.print(my); Serial.print(" mG "); 454 | Serial.print("Z-mag field: "); Serial.print(mz); Serial.println(" mG"); 455 | 456 | tempCount = readTempData(); // Read the adc values 457 | temperature = ((float) tempCount) / 333.87 + 21.0; // Temperature in degrees Centigrade 458 | // Print temperature in degrees Centigrade 459 | Serial.print("Temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C 460 | } 461 | 462 | display.clearDisplay(); 463 | display.setCursor(0, 0); display.print("MPU9250/AK8963"); 464 | display.setCursor(0, 8); display.print(" x y z "); 465 | 466 | display.setCursor(0, 16); display.print((int)(1000*ax)); 467 | display.setCursor(24, 16); display.print((int)(1000*ay)); 468 | display.setCursor(48, 16); display.print((int)(1000*az)); 469 | display.setCursor(72, 16); display.print("mg"); 470 | 471 | display.setCursor(0, 24); display.print((int)(gx)); 472 | display.setCursor(24, 24); display.print((int)(gy)); 473 | display.setCursor(48, 24); display.print((int)(gz)); 474 | display.setCursor(66, 24); display.print("o/s"); 475 | 476 | display.setCursor(0, 32); display.print((int)(mx)); 477 | display.setCursor(24, 32); display.print((int)(my)); 478 | display.setCursor(48, 32); display.print((int)(mz)); 479 | display.setCursor(72, 32); display.print("mG"); 480 | 481 | display.setCursor(0, 40); display.print("Gyro T "); 482 | display.setCursor(50, 40); display.print(temperature, 1); display.print(" C"); 483 | display.display(); 484 | 485 | count = millis(); 486 | digitalWrite(myLed, !digitalRead(myLed)); // toggle led 487 | } 488 | } 489 | else { 490 | 491 | // Serial print and/or display at 0.5 s rate independent of data rates 492 | delt_t = millis() - count; 493 | if (delt_t > 500) { // update LCD once per half-second independent of read rate 494 | 495 | if(SerialDebug) { 496 | Serial.print("ax = "); Serial.print((int)1000*ax); 497 | Serial.print(" ay = "); Serial.print((int)1000*ay); 498 | Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); 499 | Serial.print("gx = "); Serial.print( gx, 2); 500 | Serial.print(" gy = "); Serial.print( gy, 2); 501 | Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); 502 | Serial.print("mx = "); Serial.print( (int)mx ); 503 | Serial.print(" my = "); Serial.print( (int)my ); 504 | Serial.print(" mz = "); Serial.print( (int)mz ); Serial.println(" mG"); 505 | 506 | Serial.print("q0 = "); Serial.print(q[0]); 507 | Serial.print(" qx = "); Serial.print(q[1]); 508 | Serial.print(" qy = "); Serial.print(q[2]); 509 | Serial.print(" qz = "); Serial.println(q[3]); 510 | } 511 | 512 | // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 513 | // In this coordinate system, the positive z-axis is down toward Earth. 514 | // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 515 | // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 516 | // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 517 | // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 518 | // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 519 | // applied in the correct order which for this configuration is yaw, pitch, and then roll. 520 | // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 521 | 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]); 522 | pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 523 | 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]); 524 | pitch *= 180.0f / PI; 525 | yaw *= 180.0f / PI; 526 | yaw -= 13.8; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 527 | roll *= 180.0f / PI; 528 | 529 | if(SerialDebug) { 530 | Serial.print("Yaw, Pitch, Roll: "); 531 | Serial.print(yaw, 2); 532 | Serial.print(", "); 533 | Serial.print(pitch, 2); 534 | Serial.print(", "); 535 | Serial.println(roll, 2); 536 | 537 | Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); 538 | } 539 | 540 | display.clearDisplay(); 541 | 542 | display.setCursor(0, 0); display.print(" x y z "); 543 | 544 | display.setCursor(0, 8); display.print((int)(1000*ax)); 545 | display.setCursor(24, 8); display.print((int)(1000*ay)); 546 | display.setCursor(48, 8); display.print((int)(1000*az)); 547 | display.setCursor(72, 8); display.print("mg"); 548 | 549 | display.setCursor(0, 16); display.print((int)(gx)); 550 | display.setCursor(24, 16); display.print((int)(gy)); 551 | display.setCursor(48, 16); display.print((int)(gz)); 552 | display.setCursor(66, 16); display.print("o/s"); 553 | 554 | display.setCursor(0, 24); display.print((int)(mx)); 555 | display.setCursor(24, 24); display.print((int)(my)); 556 | display.setCursor(48, 24); display.print((int)(mz)); 557 | display.setCursor(72, 24); display.print("mG"); 558 | 559 | display.setCursor(0, 32); display.print((int)(yaw)); 560 | display.setCursor(24, 32); display.print((int)(pitch)); 561 | display.setCursor(48, 32); display.print((int)(roll)); 562 | display.setCursor(66, 32); display.print("ypr"); 563 | 564 | // With these settings the filter is updating at a ~145 Hz rate using the Madgwick scheme and 565 | // >200 Hz using the Mahony scheme even though the display refreshes at only 2 Hz. 566 | // The filter update rate is determined mostly by the mathematical steps in the respective algorithms, 567 | // the processor speed (8 MHz for the 3.3V Pro Mini), and the magnetometer ODR: 568 | // an ODR of 10 Hz for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces 569 | // filter update rates of 36 - 145 and ~38 Hz for the Madgwick and Mahony schemes, respectively. 570 | // This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads. 571 | // This filter update rate should be fast enough to maintain accurate platform orientation for 572 | // stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz 573 | // produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors. 574 | // The 3.3 V 8 MHz Pro Mini is doing pretty well! 575 | display.setCursor(0, 40); display.print("rt: "); display.print((float) sumCount / sum, 2); display.print(" Hz"); 576 | display.display(); 577 | 578 | count = millis(); 579 | sumCount = 0; 580 | sum = 0; 581 | } 582 | } 583 | 584 | } 585 | 586 | //=================================================================================================================== 587 | //====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data 588 | //=================================================================================================================== 589 | 590 | void getMres() { 591 | switch (Mscale) 592 | { 593 | // Possible magnetometer scales (and their register bit settings) are: 594 | // 14 bit resolution (0) and 16 bit resolution (1) 595 | case MFS_14BITS: 596 | mRes = 10.*4912./8190.; // Proper scale to return milliGauss 597 | break; 598 | case MFS_16BITS: 599 | mRes = 10.*4912./32760.0; // Proper scale to return milliGauss 600 | break; 601 | } 602 | } 603 | 604 | void getGres() { 605 | switch (Gscale) 606 | { 607 | // Possible gyro scales (and their register bit settings) are: 608 | // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 609 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 610 | case GFS_250DPS: 611 | gRes = 250.0/32768.0; 612 | break; 613 | case GFS_500DPS: 614 | gRes = 500.0/32768.0; 615 | break; 616 | case GFS_1000DPS: 617 | gRes = 1000.0/32768.0; 618 | break; 619 | case GFS_2000DPS: 620 | gRes = 2000.0/32768.0; 621 | break; 622 | } 623 | } 624 | 625 | void getAres() { 626 | switch (Ascale) 627 | { 628 | // Possible accelerometer scales (and their register bit settings) are: 629 | // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 630 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 631 | case AFS_2G: 632 | aRes = 2.0/32768.0; 633 | break; 634 | case AFS_4G: 635 | aRes = 4.0/32768.0; 636 | break; 637 | case AFS_8G: 638 | aRes = 8.0/32768.0; 639 | break; 640 | case AFS_16G: 641 | aRes = 16.0/32768.0; 642 | break; 643 | } 644 | } 645 | 646 | 647 | void readAccelData(int16_t * destination) 648 | { 649 | uint8_t rawData[6]; // x/y/z accel register data stored here 650 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 651 | destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value 652 | destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; 653 | destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; 654 | } 655 | 656 | 657 | void readGyroData(int16_t * destination) 658 | { 659 | uint8_t rawData[6]; // x/y/z gyro register data stored here 660 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 661 | destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value 662 | destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; 663 | destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; 664 | } 665 | 666 | void readMagData(int16_t * destination) 667 | { 668 | uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 669 | if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 670 | readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 671 | uint8_t c = rawData[6]; // End data read by reading ST2 register 672 | if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data 673 | destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value 674 | destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; // Data stored as little Endian 675 | destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; 676 | } 677 | } 678 | } 679 | 680 | int16_t readTempData() 681 | { 682 | uint8_t rawData[2]; // x/y/z gyro register data stored here 683 | readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 684 | return ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a 16-bit value 685 | } 686 | 687 | void initAK8963(float * destination) 688 | { 689 | // First extract the factory calibration for each magnetometer axis 690 | uint8_t rawData[3]; // x/y/z gyro calibration data stored here 691 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 692 | delay(10); 693 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 694 | delay(10); 695 | readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 696 | destination[0] = (float)(rawData[0] - 128)/256. + 1.; // Return x-axis sensitivity adjustment values, etc. 697 | destination[1] = (float)(rawData[1] - 128)/256. + 1.; 698 | destination[2] = (float)(rawData[2] - 128)/256. + 1.; 699 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 700 | delay(10); 701 | // Configure the magnetometer for continuous read and highest resolution 702 | // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 703 | // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 704 | writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 705 | delay(10); 706 | } 707 | 708 | 709 | void initMPU9250() 710 | { 711 | // wake up device 712 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 713 | delay(100); // Wait for all registers to reset 714 | 715 | // get stable time source 716 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Auto select clock source to be PLL gyroscope reference if ready else 717 | delay(200); 718 | 719 | // Configure Gyro and Thermometer 720 | // Disable FSYNC and set thermometer and gyro bandwidth to 41 and 42 Hz, respectively; 721 | // minimum delay time for this setting is 5.9 ms, which means sensor fusion update rates cannot 722 | // be higher than 1 / 0.0059 = 170 Hz 723 | // DLPF_CFG = bits 2:0 = 011; this limits the sample rate to 1000 Hz for both 724 | // With the MPU9250, it is possible to get gyro sample rates of 32 kHz (!), 8 kHz, or 1 kHz 725 | writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 726 | 727 | // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 728 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; a rate consistent with the filter update rate 729 | // determined inset in CONFIG above 730 | 731 | // Set gyroscope full scale range 732 | // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 733 | uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 734 | // writeRegister(GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 735 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x02); // Clear Fchoice bits [1:0] 736 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 737 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 738 | // writeRegister(GYRO_CONFIG, c | 0x00); // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG 739 | 740 | // Set accelerometer full-scale range configuration 741 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 742 | // writeRegister(ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 743 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 744 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 745 | 746 | // Set accelerometer sample rate configuration 747 | // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 748 | // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 749 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 750 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 751 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 752 | 753 | // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 754 | // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 755 | 756 | // Configure Interrupts and Bypass Enable 757 | // Set interrupt pin active high, push-pull, hold interrupt pin level HIGH until interrupt cleared, 758 | // clear on read of INT_STATUS, and enable I2C_BYPASS_EN so additional chips 759 | // can join the I2C bus and all can be controlled by the Arduino as master 760 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 761 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 762 | delay(100); 763 | } 764 | 765 | 766 | // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 767 | // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 768 | void calibrateMPU9250(float * dest1, float * dest2) 769 | { 770 | uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 771 | uint16_t ii, packet_count, fifo_count; 772 | int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 773 | 774 | // reset device 775 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 776 | delay(100); 777 | 778 | // get stable time source; Auto select clock source to be PLL gyroscope reference if ready 779 | // else use the internal oscillator, bits 2:0 = 001 780 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 781 | writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 782 | delay(200); 783 | 784 | // Configure device for bias calculation 785 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 786 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 787 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 788 | writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 789 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 790 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 791 | delay(15); 792 | 793 | // Configure MPU6050 gyro and accelerometer for bias calculation 794 | writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 795 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 796 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 797 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 798 | 799 | uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 800 | uint16_t accelsensitivity = 16384; // = 16384 LSB/g 801 | 802 | // Configure FIFO to capture accelerometer and gyro data for bias calculation 803 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 804 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9150) 805 | delay(40); // accumulate 40 samples in 40 milliseconds = 480 bytes 806 | 807 | // At end of sample accumulation, turn off FIFO sensor read 808 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 809 | readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 810 | fifo_count = ((uint16_t)data[0] << 8) | data[1]; 811 | packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 812 | 813 | for (ii = 0; ii < packet_count; ii++) { 814 | int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 815 | readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 816 | accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 817 | accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 818 | accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 819 | gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 820 | gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 821 | gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 822 | 823 | accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 824 | accel_bias[1] += (int32_t) accel_temp[1]; 825 | accel_bias[2] += (int32_t) accel_temp[2]; 826 | gyro_bias[0] += (int32_t) gyro_temp[0]; 827 | gyro_bias[1] += (int32_t) gyro_temp[1]; 828 | gyro_bias[2] += (int32_t) gyro_temp[2]; 829 | 830 | } 831 | accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 832 | accel_bias[1] /= (int32_t) packet_count; 833 | accel_bias[2] /= (int32_t) packet_count; 834 | gyro_bias[0] /= (int32_t) packet_count; 835 | gyro_bias[1] /= (int32_t) packet_count; 836 | gyro_bias[2] /= (int32_t) packet_count; 837 | 838 | if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 839 | else {accel_bias[2] += (int32_t) accelsensitivity;} 840 | 841 | // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 842 | 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 843 | data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 844 | data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 845 | data[3] = (-gyro_bias[1]/4) & 0xFF; 846 | data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 847 | data[5] = (-gyro_bias[2]/4) & 0xFF; 848 | 849 | // Push gyro biases to hardware registers 850 | writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 851 | writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 852 | writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 853 | writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 854 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 855 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 856 | 857 | // Output scaled gyro biases for display in the main program 858 | dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; 859 | dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 860 | dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 861 | 862 | // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 863 | // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 864 | // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 865 | // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 866 | // the accelerometer biases calculated above must be divided by 8. 867 | 868 | int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 869 | readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 870 | accel_bias_reg[0] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 871 | readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 872 | accel_bias_reg[1] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 873 | readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 874 | accel_bias_reg[2] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 875 | 876 | uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 877 | uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 878 | 879 | for(ii = 0; ii < 3; ii++) { 880 | if((accel_bias_reg[ii] & mask)) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 881 | } 882 | 883 | // Construct total accelerometer bias, including calculated average accelerometer bias from above 884 | accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 885 | accel_bias_reg[1] -= (accel_bias[1]/8); 886 | accel_bias_reg[2] -= (accel_bias[2]/8); 887 | 888 | data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 889 | data[1] = (accel_bias_reg[0]) & 0xFF; 890 | data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 891 | data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 892 | data[3] = (accel_bias_reg[1]) & 0xFF; 893 | data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 894 | data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 895 | data[5] = (accel_bias_reg[2]) & 0xFF; 896 | data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 897 | 898 | // Apparently this is not working for the acceleration biases in the MPU-9250 899 | // Are we handling the temperature correction bit properly? 900 | // Push accelerometer biases to hardware registers 901 | writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 902 | writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 903 | writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 904 | writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 905 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 906 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 907 | 908 | // Output scaled accelerometer biases for display in the main program 909 | dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 910 | dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 911 | dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 912 | } 913 | 914 | 915 | // Accelerometer and gyroscope self test; check calibration wrt factory settings 916 | void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 917 | { 918 | uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 919 | uint8_t selfTest[6]; 920 | int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 921 | float factoryTrim[6]; 922 | uint8_t FS = 0; 923 | 924 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 925 | writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 926 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1< 30 | #include 31 | #include 32 | #include 33 | 34 | // Using NOKIA 5110 monochrome 84 x 48 pixel display 35 | // pin 9 - Serial clock out (SCLK) 36 | // pin 8 - Serial data out (DIN) 37 | // pin 7 - Data/Command select (D/C) 38 | // pin 5 - LCD chip select (CS) 39 | // pin 6 - LCD reset (RST) 40 | Adafruit_PCD8544 display = Adafruit_PCD8544(9, 8, 7, 5, 6); 41 | 42 | // See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in 43 | // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map 44 | // 45 | //Magnetometer Registers 46 | #define AK8963_ADDRESS 0x0C 47 | #define WHO_AM_I_AK8963 0x00 // should return 0x48 48 | #define INFO 0x01 49 | #define AK8963_ST1 0x02 // data ready status bit 0 50 | #define AK8963_XOUT_L 0x03 // data 51 | #define AK8963_XOUT_H 0x04 52 | #define AK8963_YOUT_L 0x05 53 | #define AK8963_YOUT_H 0x06 54 | #define AK8963_ZOUT_L 0x07 55 | #define AK8963_ZOUT_H 0x08 56 | #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 57 | #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 58 | #define AK8963_ASTC 0x0C // Self test control 59 | #define AK8963_I2CDIS 0x0F // I2C disable 60 | #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value 61 | #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value 62 | #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value 63 | 64 | #define SELF_TEST_X_GYRO 0x00 65 | #define SELF_TEST_Y_GYRO 0x01 66 | #define SELF_TEST_Z_GYRO 0x02 67 | 68 | /*#define X_FINE_GAIN 0x03 // [7:0] fine gain 69 | #define Y_FINE_GAIN 0x04 70 | #define Z_FINE_GAIN 0x05 71 | #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 72 | #define XA_OFFSET_L_TC 0x07 73 | #define YA_OFFSET_H 0x08 74 | #define YA_OFFSET_L_TC 0x09 75 | #define ZA_OFFSET_H 0x0A 76 | #define ZA_OFFSET_L_TC 0x0B */ 77 | 78 | #define SELF_TEST_X_ACCEL 0x0D 79 | #define SELF_TEST_Y_ACCEL 0x0E 80 | #define SELF_TEST_Z_ACCEL 0x0F 81 | 82 | #define SELF_TEST_A 0x10 83 | 84 | #define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope 85 | #define XG_OFFSET_L 0x14 86 | #define YG_OFFSET_H 0x15 87 | #define YG_OFFSET_L 0x16 88 | #define ZG_OFFSET_H 0x17 89 | #define ZG_OFFSET_L 0x18 90 | #define SMPLRT_DIV 0x19 91 | #define CONFIG 0x1A 92 | #define GYRO_CONFIG 0x1B 93 | #define ACCEL_CONFIG 0x1C 94 | #define ACCEL_CONFIG2 0x1D 95 | #define LP_ACCEL_ODR 0x1E 96 | #define WOM_THR 0x1F 97 | 98 | #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms 99 | #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] 100 | #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms 101 | 102 | #define FIFO_EN 0x23 103 | #define I2C_MST_CTRL 0x24 104 | #define I2C_SLV0_ADDR 0x25 105 | #define I2C_SLV0_REG 0x26 106 | #define I2C_SLV0_CTRL 0x27 107 | #define I2C_SLV1_ADDR 0x28 108 | #define I2C_SLV1_REG 0x29 109 | #define I2C_SLV1_CTRL 0x2A 110 | #define I2C_SLV2_ADDR 0x2B 111 | #define I2C_SLV2_REG 0x2C 112 | #define I2C_SLV2_CTRL 0x2D 113 | #define I2C_SLV3_ADDR 0x2E 114 | #define I2C_SLV3_REG 0x2F 115 | #define I2C_SLV3_CTRL 0x30 116 | #define I2C_SLV4_ADDR 0x31 117 | #define I2C_SLV4_REG 0x32 118 | #define I2C_SLV4_DO 0x33 119 | #define I2C_SLV4_CTRL 0x34 120 | #define I2C_SLV4_DI 0x35 121 | #define I2C_MST_STATUS 0x36 122 | #define INT_PIN_CFG 0x37 123 | #define INT_ENABLE 0x38 124 | #define DMP_INT_STATUS 0x39 // Check DMP interrupt 125 | #define INT_STATUS 0x3A 126 | #define ACCEL_XOUT_H 0x3B 127 | #define ACCEL_XOUT_L 0x3C 128 | #define ACCEL_YOUT_H 0x3D 129 | #define ACCEL_YOUT_L 0x3E 130 | #define ACCEL_ZOUT_H 0x3F 131 | #define ACCEL_ZOUT_L 0x40 132 | #define TEMP_OUT_H 0x41 133 | #define TEMP_OUT_L 0x42 134 | #define GYRO_XOUT_H 0x43 135 | #define GYRO_XOUT_L 0x44 136 | #define GYRO_YOUT_H 0x45 137 | #define GYRO_YOUT_L 0x46 138 | #define GYRO_ZOUT_H 0x47 139 | #define GYRO_ZOUT_L 0x48 140 | #define EXT_SENS_DATA_00 0x49 141 | #define EXT_SENS_DATA_01 0x4A 142 | #define EXT_SENS_DATA_02 0x4B 143 | #define EXT_SENS_DATA_03 0x4C 144 | #define EXT_SENS_DATA_04 0x4D 145 | #define EXT_SENS_DATA_05 0x4E 146 | #define EXT_SENS_DATA_06 0x4F 147 | #define EXT_SENS_DATA_07 0x50 148 | #define EXT_SENS_DATA_08 0x51 149 | #define EXT_SENS_DATA_09 0x52 150 | #define EXT_SENS_DATA_10 0x53 151 | #define EXT_SENS_DATA_11 0x54 152 | #define EXT_SENS_DATA_12 0x55 153 | #define EXT_SENS_DATA_13 0x56 154 | #define EXT_SENS_DATA_14 0x57 155 | #define EXT_SENS_DATA_15 0x58 156 | #define EXT_SENS_DATA_16 0x59 157 | #define EXT_SENS_DATA_17 0x5A 158 | #define EXT_SENS_DATA_18 0x5B 159 | #define EXT_SENS_DATA_19 0x5C 160 | #define EXT_SENS_DATA_20 0x5D 161 | #define EXT_SENS_DATA_21 0x5E 162 | #define EXT_SENS_DATA_22 0x5F 163 | #define EXT_SENS_DATA_23 0x60 164 | #define MOT_DETECT_STATUS 0x61 165 | #define I2C_SLV0_DO 0x63 166 | #define I2C_SLV1_DO 0x64 167 | #define I2C_SLV2_DO 0x65 168 | #define I2C_SLV3_DO 0x66 169 | #define I2C_MST_DELAY_CTRL 0x67 170 | #define SIGNAL_PATH_RESET 0x68 171 | #define MOT_DETECT_CTRL 0x69 172 | #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP 173 | #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode 174 | #define PWR_MGMT_2 0x6C 175 | #define DMP_BANK 0x6D // Activates a specific bank in the DMP 176 | #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank 177 | #define DMP_REG 0x6F // Register in DMP from which to read or to which to write 178 | #define DMP_REG_1 0x70 179 | #define DMP_REG_2 0x71 180 | #define FIFO_COUNTH 0x72 181 | #define FIFO_COUNTL 0x73 182 | #define FIFO_R_W 0x74 183 | #define WHO_AM_I_MPU9250 0x75 // Should return 0x71 184 | #define XA_OFFSET_H 0x77 185 | #define XA_OFFSET_L 0x78 186 | #define YA_OFFSET_H 0x7A 187 | #define YA_OFFSET_L 0x7B 188 | #define ZA_OFFSET_H 0x7D 189 | #define ZA_OFFSET_L 0x7E 190 | 191 | // Using the MSENSR-9250 breakout board, ADO is set to 0 192 | // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 193 | //#define ADO 0 194 | #if ADO 195 | #define MPU9250_ADDRESS 0x69 // Device address when ADO = 1 196 | #else 197 | #define MPU9250_ADDRESS 0x68 // Device address when ADO = 0 198 | #define AK8963_ADDRESS 0x0C // Address of magnetometer 199 | #endif 200 | 201 | #define AHRS true // set to false for basic data read 202 | #define SerialDebug true // set to true to get Serial output for debugging 203 | 204 | // Set initial input parameters 205 | enum Ascale { 206 | AFS_2G = 0, 207 | AFS_4G, 208 | AFS_8G, 209 | AFS_16G 210 | }; 211 | 212 | enum Gscale { 213 | GFS_250DPS = 0, 214 | GFS_500DPS, 215 | GFS_1000DPS, 216 | GFS_2000DPS 217 | }; 218 | 219 | enum Mscale { 220 | MFS_14BITS = 0, // 0.6 mG per LSB 221 | MFS_16BITS // 0.15 mG per LSB 222 | }; 223 | 224 | // Specify sensor full scale 225 | uint8_t Gscale = GFS_250DPS; 226 | uint8_t Ascale = AFS_2G; 227 | uint8_t Mscale = MFS_16BITS; // Choose either 14-bit or 16-bit magnetometer resolution 228 | uint8_t Mmode = 0x02; // 2 for 8 Hz, 6 for 100 Hz continuous magnetometer data read 229 | float aRes, gRes, mRes; // scale resolutions per LSB for the sensors 230 | 231 | // Pin definitions 232 | int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 233 | int adoPin = 8; 234 | int myLed = 13; 235 | 236 | int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 237 | int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 238 | int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output 239 | float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias 240 | float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 241 | int16_t tempCount; // temperature raw count output 242 | float temperature; // Stores the real internal chip temperature in degrees Celsius 243 | float SelfTest[6]; // holds results of gyro and accelerometer self test 244 | 245 | // global constants for 9 DoF fusion and AHRS (Attitude and Heading Reference System) 246 | float GyroMeasError = PI * (40.0f / 180.0f); // gyroscope measurement error in rads/s (start at 40 deg/s) 247 | float GyroMeasDrift = PI * (0.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 248 | // There is a tradeoff in the beta parameter between accuracy and response speed. 249 | // In the original Madgwick study, beta of 0.041 (corresponding to GyroMeasError of 2.7 degrees/s) was found to give optimal accuracy. 250 | // However, with this value, the LSM9SD0 response time is about 10 seconds to a stable initial quaternion. 251 | // Subsequent changes also require a longish lag time to a stable output, not fast enough for a quadcopter or robot car! 252 | // By increasing beta (GyroMeasError) by about a factor of fifteen, the response time constant is reduced to ~2 sec 253 | // I haven't noticed any reduction in solution accuracy. This is essentially the I coefficient in a PID control sense; 254 | // the bigger the feedback coefficient, the faster the solution converges, usually at the expense of accuracy. 255 | // In any case, this is the free parameter in the Madgwick filtering and fusion scheme. 256 | float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 257 | 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 258 | #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 259 | #define Ki 0.0f 260 | 261 | uint32_t delt_t = 0; // used to control display output rate 262 | uint32_t count = 0, sumCount = 0; // used to control display output rate 263 | float pitch, yaw, roll; 264 | float deltat = 0.0f, sum = 0.0f; // integration interval for both filter schemes 265 | uint32_t lastUpdate = 0, firstUpdate = 0; // used to calculate integration interval 266 | uint32_t Now = 0; // used to calculate integration interval 267 | 268 | float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values 269 | float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 270 | float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method 271 | 272 | 273 | void setup() 274 | { 275 | // Wire.begin(); 276 | // TWBR = 12; // 400 kbit/sec I2C speed 277 | // Setup for Master mode, pins 18/19, external pullups, 400kHz 278 | Wire.begin(I2C_MASTER, 0x00, I2C_PINS_16_17, I2C_PULLUP_EXT, I2C_RATE_100); 279 | Serial.begin(38400); 280 | 281 | // Set up the interrupt pin, its set as active high, push-pull 282 | pinMode(intPin, INPUT); 283 | digitalWrite(intPin, LOW); 284 | pinMode(adoPin, OUTPUT); 285 | digitalWrite(adoPin, HIGH); 286 | pinMode(myLed, OUTPUT); 287 | digitalWrite(myLed, HIGH); 288 | 289 | display.begin(); // Initialize the display 290 | display.setContrast(58); // Set the contrast 291 | 292 | // Start device display with ID of sensor 293 | display.clearDisplay(); 294 | display.setTextSize(2); 295 | display.setCursor(0,0); display.print("MPU9250"); 296 | display.setTextSize(1); 297 | display.setCursor(0, 20); display.print("9-DOF 16-bit"); 298 | display.setCursor(0, 30); display.print("motion sensor"); 299 | display.setCursor(20,40); display.print("60 ug LSB"); 300 | display.display(); 301 | delay(1000); 302 | 303 | // Set up for data display 304 | display.setTextSize(1); // Set text size to normal, 2 is twice normal etc. 305 | display.setTextColor(BLACK); // Set pixel color; 1 on the monochrome screen 306 | display.clearDisplay(); // clears the screen and buffer 307 | 308 | // Read the WHO_AM_I register, this is a good test of communication 309 | byte c = readByte(MPU9250_ADDRESS, WHO_AM_I_MPU9250); // Read WHO_AM_I register for MPU-9250 310 | Serial.print("MPU9250 "); Serial.print("I AM "); Serial.print(c, HEX); Serial.print(" I should be "); Serial.println(0x71, HEX); 311 | display.setCursor(20,0); display.print("MPU9250"); 312 | display.setCursor(0,10); display.print("I AM"); 313 | display.setCursor(0,20); display.print(c, HEX); 314 | display.setCursor(0,30); display.print("I Should Be"); 315 | display.setCursor(0,40); display.print(0x71, HEX); 316 | display.display(); 317 | delay(5000); 318 | 319 | if (c == 0x71) // WHO_AM_I should always be 0x68 320 | { 321 | Serial.println("MPU9250 is online..."); 322 | 323 | MPU9250SelfTest(SelfTest); // Start by performing self test and reporting values 324 | Serial.print("x-axis self test: acceleration trim within : "); Serial.print(SelfTest[0],1); Serial.println("% of factory value"); 325 | Serial.print("y-axis self test: acceleration trim within : "); Serial.print(SelfTest[1],1); Serial.println("% of factory value"); 326 | Serial.print("z-axis self test: acceleration trim within : "); Serial.print(SelfTest[2],1); Serial.println("% of factory value"); 327 | Serial.print("x-axis self test: gyration trim within : "); Serial.print(SelfTest[3],1); Serial.println("% of factory value"); 328 | Serial.print("y-axis self test: gyration trim within : "); Serial.print(SelfTest[4],1); Serial.println("% of factory value"); 329 | Serial.print("z-axis self test: gyration trim within : "); Serial.print(SelfTest[5],1); Serial.println("% of factory value"); 330 | delay(5000); 331 | 332 | calibrateMPU9250(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 333 | display.clearDisplay(); 334 | 335 | display.setCursor(0, 0); display.print("MPU9250 bias"); 336 | display.setCursor(0, 8); display.print(" x y z "); 337 | 338 | display.setCursor(0, 16); display.print((int)(1000*accelBias[0])); 339 | display.setCursor(24, 16); display.print((int)(1000*accelBias[1])); 340 | display.setCursor(48, 16); display.print((int)(1000*accelBias[2])); 341 | display.setCursor(72, 16); display.print("mg"); 342 | 343 | display.setCursor(0, 24); display.print(gyroBias[0], 1); 344 | display.setCursor(24, 24); display.print(gyroBias[1], 1); 345 | display.setCursor(48, 24); display.print(gyroBias[2], 1); 346 | display.setCursor(66, 24); display.print("o/s"); 347 | 348 | display.display(); 349 | delay(1000); 350 | 351 | initMPU9250(); 352 | Serial.println("MPU9250 initialized for active data mode...."); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 353 | 354 | // Read the WHO_AM_I register of the magnetometer, this is a good test of communication 355 | byte d = readByte(AK8963_ADDRESS, WHO_AM_I_AK8963); // Read WHO_AM_I register for AK8963 356 | Serial.print("AK8963 "); Serial.print("I AM "); Serial.print(d, HEX); Serial.print(" I should be "); Serial.println(0x48, HEX); 357 | display.clearDisplay(); 358 | display.setCursor(20,0); display.print("AK8963"); 359 | display.setCursor(0,10); display.print("I AM"); 360 | display.setCursor(0,20); display.print(d, HEX); 361 | display.setCursor(0,30); display.print("I Should Be"); 362 | display.setCursor(0,40); display.print(0x48, HEX); 363 | display.display(); 364 | delay(1000); 365 | 366 | // Get magnetometer calibration from AK8963 ROM 367 | initAK8963(magCalibration); Serial.println("AK8963 initialized for active data mode...."); // Initialize device for active mode read of magnetometer 368 | 369 | if(SerialDebug) { 370 | // Serial.println("Calibration values: "); 371 | Serial.print("X-Axis sensitivity adjustment value "); Serial.println(magCalibration[0], 2); 372 | Serial.print("Y-Axis sensitivity adjustment value "); Serial.println(magCalibration[1], 2); 373 | Serial.print("Z-Axis sensitivity adjustment value "); Serial.println(magCalibration[2], 2); 374 | } 375 | 376 | display.clearDisplay(); 377 | display.setCursor(20,0); display.print("AK8963"); 378 | display.setCursor(0,10); display.print("ASAX "); display.setCursor(50,10); display.print(magCalibration[0], 2); 379 | display.setCursor(0,20); display.print("ASAY "); display.setCursor(50,20); display.print(magCalibration[1], 2); 380 | display.setCursor(0,30); display.print("ASAZ "); display.setCursor(50,30); display.print(magCalibration[2], 2); 381 | display.display(); 382 | delay(1000); 383 | } 384 | else 385 | { 386 | Serial.print("Could not connect to MPU9250: 0x"); 387 | Serial.println(c, HEX); 388 | while(1) ; // Loop forever if communication doesn't happen 389 | } 390 | } 391 | 392 | void loop() 393 | { 394 | // If intPin goes high, all data registers have new data 395 | if (readByte(MPU9250_ADDRESS, INT_STATUS) & 0x01) { // On interrupt, check if data ready interrupt 396 | readAccelData(accelCount); // Read the x/y/z adc values 397 | getAres(); 398 | 399 | // Now we'll calculate the accleration value into actual g's 400 | ax = (float)accelCount[0]*aRes; // - accelBias[0]; // get actual g value, this depends on scale being set 401 | ay = (float)accelCount[1]*aRes; // - accelBias[1]; 402 | az = (float)accelCount[2]*aRes; // - accelBias[2]; 403 | 404 | readGyroData(gyroCount); // Read the x/y/z adc values 405 | getGres(); 406 | 407 | // Calculate the gyro value into actual degrees per second 408 | gx = (float)gyroCount[0]*gRes; // get actual gyro value, this depends on scale being set 409 | gy = (float)gyroCount[1]*gRes; 410 | gz = (float)gyroCount[2]*gRes; 411 | 412 | readMagData(magCount); // Read the x/y/z adc values 413 | getMres(); 414 | magbias[0] = +470.; // User environmental x-axis correction in milliGauss, should be automatically calculated 415 | magbias[1] = +120.; // User environmental x-axis correction in milliGauss 416 | magbias[2] = +125.; // User environmental x-axis correction in milliGauss 417 | 418 | // Calculate the magnetometer values in milliGauss 419 | // Include factory calibration per data sheet and user environmental corrections 420 | mx = (float)magCount[0]*mRes*magCalibration[0] - magbias[0]; // get actual magnetometer value, this depends on scale being set 421 | my = (float)magCount[1]*mRes*magCalibration[1] - magbias[1]; 422 | mz = (float)magCount[2]*mRes*magCalibration[2] - magbias[2]; 423 | } 424 | 425 | Now = micros(); 426 | deltat = ((Now - lastUpdate)/1000000.0f); // set integration time by time elapsed since last filter update 427 | lastUpdate = Now; 428 | 429 | sum += deltat; // sum for averaging filter update rate 430 | sumCount++; 431 | 432 | // Sensors x (y)-axis of the accelerometer is aligned with the y (x)-axis of the magnetometer; 433 | // the magnetometer z-axis (+ down) is opposite to z-axis (+ up) of accelerometer and gyro! 434 | // We have to make some allowance for this orientationmismatch in feeding the output to the quaternion filter. 435 | // For the MPU-9250, we have chosen a magnetic rotation that keeps the sensor forward along the x-axis just like 436 | // in the LSM9DS0 sensor. This rotation can be modified to allow any convenient orientation convention. 437 | // This is ok by aircraft orientation standards! 438 | // Pass gyro rate as rad/s 439 | MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 440 | // MahonyQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); 441 | 442 | 443 | if (!AHRS) { 444 | delt_t = millis() - count; 445 | if(delt_t > 500) { 446 | 447 | if(SerialDebug) { 448 | // Print acceleration values in milligs! 449 | Serial.print("X-acceleration: "); Serial.print(1000*ax); Serial.print(" mg "); 450 | Serial.print("Y-acceleration: "); Serial.print(1000*ay); Serial.print(" mg "); 451 | Serial.print("Z-acceleration: "); Serial.print(1000*az); Serial.println(" mg "); 452 | 453 | // Print gyro values in degree/sec 454 | Serial.print("X-gyro rate: "); Serial.print(gx, 3); Serial.print(" degrees/sec "); 455 | Serial.print("Y-gyro rate: "); Serial.print(gy, 3); Serial.print(" degrees/sec "); 456 | Serial.print("Z-gyro rate: "); Serial.print(gz, 3); Serial.println(" degrees/sec"); 457 | 458 | // Print mag values in degree/sec 459 | Serial.print("X-mag field: "); Serial.print(mx); Serial.print(" mG "); 460 | Serial.print("Y-mag field: "); Serial.print(my); Serial.print(" mG "); 461 | Serial.print("Z-mag field: "); Serial.print(mz); Serial.println(" mG"); 462 | 463 | tempCount = readTempData(); // Read the adc values 464 | temperature = ((float) tempCount) / 333.87 + 21.0; // Temperature in degrees Centigrade 465 | // Print temperature in degrees Centigrade 466 | Serial.print("Temperature is "); Serial.print(temperature, 1); Serial.println(" degrees C"); // Print T values to tenths of s degree C 467 | } 468 | 469 | display.clearDisplay(); 470 | display.setCursor(0, 0); display.print("MPU9250/AK8963"); 471 | display.setCursor(0, 8); display.print(" x y z "); 472 | 473 | display.setCursor(0, 16); display.print((int)(1000*ax)); 474 | display.setCursor(24, 16); display.print((int)(1000*ay)); 475 | display.setCursor(48, 16); display.print((int)(1000*az)); 476 | display.setCursor(72, 16); display.print("mg"); 477 | 478 | display.setCursor(0, 24); display.print((int)(gx)); 479 | display.setCursor(24, 24); display.print((int)(gy)); 480 | display.setCursor(48, 24); display.print((int)(gz)); 481 | display.setCursor(66, 24); display.print("o/s"); 482 | 483 | display.setCursor(0, 32); display.print((int)(mx)); 484 | display.setCursor(24, 32); display.print((int)(my)); 485 | display.setCursor(48, 32); display.print((int)(mz)); 486 | display.setCursor(72, 32); display.print("mG"); 487 | 488 | display.setCursor(0, 40); display.print("Gyro T "); 489 | display.setCursor(50, 40); display.print(temperature, 1); display.print(" C"); 490 | display.display(); 491 | 492 | count = millis(); 493 | } 494 | } 495 | else { 496 | 497 | // Serial print and/or display at 0.5 s rate independent of data rates 498 | delt_t = millis() - count; 499 | if (delt_t > 500) { // update LCD once per half-second independent of read rate 500 | 501 | if(SerialDebug) { 502 | Serial.print("ax = "); Serial.print((int)1000*ax); 503 | Serial.print(" ay = "); Serial.print((int)1000*ay); 504 | Serial.print(" az = "); Serial.print((int)1000*az); Serial.println(" mg"); 505 | Serial.print("gx = "); Serial.print( gx, 2); 506 | Serial.print(" gy = "); Serial.print( gy, 2); 507 | Serial.print(" gz = "); Serial.print( gz, 2); Serial.println(" deg/s"); 508 | Serial.print("mx = "); Serial.print( (int)mx ); 509 | Serial.print(" my = "); Serial.print( (int)my ); 510 | Serial.print(" mz = "); Serial.print( (int)mz ); Serial.println(" mG"); 511 | 512 | Serial.print("q0 = "); Serial.print(q[0]); 513 | Serial.print(" qx = "); Serial.print(q[1]); 514 | Serial.print(" qy = "); Serial.print(q[2]); 515 | Serial.print(" qz = "); Serial.println(q[3]); 516 | } 517 | 518 | // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. 519 | // In this coordinate system, the positive z-axis is down toward Earth. 520 | // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. 521 | // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. 522 | // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. 523 | // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. 524 | // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be 525 | // applied in the correct order which for this configuration is yaw, pitch, and then roll. 526 | // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. 527 | 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]); 528 | pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 529 | 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]); 530 | pitch *= 180.0f / PI; 531 | yaw *= 180.0f / PI; 532 | yaw -= 13.8; // Declination at Danville, California is 13 degrees 48 minutes and 47 seconds on 2014-04-04 533 | roll *= 180.0f / PI; 534 | 535 | if(SerialDebug) { 536 | Serial.print("Yaw, Pitch, Roll: "); 537 | Serial.print(yaw, 2); 538 | Serial.print(", "); 539 | Serial.print(pitch, 2); 540 | Serial.print(", "); 541 | Serial.println(roll, 2); 542 | 543 | Serial.print("rate = "); Serial.print((float)sumCount/sum, 2); Serial.println(" Hz"); 544 | } 545 | 546 | display.clearDisplay(); 547 | 548 | display.setCursor(0, 0); display.print(" x y z "); 549 | 550 | display.setCursor(0, 8); display.print((int)(1000*ax)); 551 | display.setCursor(24, 8); display.print((int)(1000*ay)); 552 | display.setCursor(48, 8); display.print((int)(1000*az)); 553 | display.setCursor(72, 8); display.print("mg"); 554 | 555 | display.setCursor(0, 16); display.print((int)(gx)); 556 | display.setCursor(24, 16); display.print((int)(gy)); 557 | display.setCursor(48, 16); display.print((int)(gz)); 558 | display.setCursor(66, 16); display.print("o/s"); 559 | 560 | display.setCursor(0, 24); display.print((int)(mx)); 561 | display.setCursor(24, 24); display.print((int)(my)); 562 | display.setCursor(48, 24); display.print((int)(mz)); 563 | display.setCursor(72, 24); display.print("mG"); 564 | 565 | display.setCursor(0, 32); display.print((int)(yaw)); 566 | display.setCursor(24, 32); display.print((int)(pitch)); 567 | display.setCursor(48, 32); display.print((int)(roll)); 568 | display.setCursor(66, 32); display.print("ypr"); 569 | 570 | // With these settings the filter is updating at a ~145 Hz rate using the Madgwick scheme and 571 | // >200 Hz using the Mahony scheme even though the display refreshes at only 2 Hz. 572 | // The filter update rate is determined mostly by the mathematical steps in the respective algorithms, 573 | // the processor speed (8 MHz for the 3.3V Pro Mini), and the magnetometer ODR: 574 | // an ODR of 10 Hz for the magnetometer produce the above rates, maximum magnetometer ODR of 100 Hz produces 575 | // filter update rates of 36 - 145 and ~38 Hz for the Madgwick and Mahony schemes, respectively. 576 | // This is presumably because the magnetometer read takes longer than the gyro or accelerometer reads. 577 | // This filter update rate should be fast enough to maintain accurate platform orientation for 578 | // stabilization control of a fast-moving robot or quadcopter. Compare to the update rate of 200 Hz 579 | // produced by the on-board Digital Motion Processor of Invensense's MPU6050 6 DoF and MPU9150 9DoF sensors. 580 | // The 3.3 V 8 MHz Pro Mini is doing pretty well! 581 | display.setCursor(0, 40); display.print("rt: "); display.print((float) sumCount / sum, 2); display.print(" Hz"); 582 | display.display(); 583 | 584 | digitalWrite(myLed, !digitalRead(myLed)); 585 | count = millis(); 586 | sumCount = 0; 587 | sum = 0; 588 | } 589 | } 590 | 591 | } 592 | 593 | //=================================================================================================================== 594 | //====== Set of useful function to access acceleration. gyroscope, magnetometer, and temperature data 595 | //=================================================================================================================== 596 | 597 | void getMres() { 598 | switch (Mscale) 599 | { 600 | // Possible magnetometer scales (and their register bit settings) are: 601 | // 14 bit resolution (0) and 16 bit resolution (1) 602 | case MFS_14BITS: 603 | mRes = 10.*4912./8190.; // Proper scale to return milliGauss 604 | break; 605 | case MFS_16BITS: 606 | mRes = 10.*4912./32760.0; // Proper scale to return milliGauss 607 | break; 608 | } 609 | } 610 | 611 | void getGres() { 612 | switch (Gscale) 613 | { 614 | // Possible gyro scales (and their register bit settings) are: 615 | // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 616 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 617 | case GFS_250DPS: 618 | gRes = 250.0/32768.0; 619 | break; 620 | case GFS_500DPS: 621 | gRes = 500.0/32768.0; 622 | break; 623 | case GFS_1000DPS: 624 | gRes = 1000.0/32768.0; 625 | break; 626 | case GFS_2000DPS: 627 | gRes = 2000.0/32768.0; 628 | break; 629 | } 630 | } 631 | 632 | void getAres() { 633 | switch (Ascale) 634 | { 635 | // Possible accelerometer scales (and their register bit settings) are: 636 | // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 637 | // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 638 | case AFS_2G: 639 | aRes = 2.0/32768.0; 640 | break; 641 | case AFS_4G: 642 | aRes = 4.0/32768.0; 643 | break; 644 | case AFS_8G: 645 | aRes = 8.0/32768.0; 646 | break; 647 | case AFS_16G: 648 | aRes = 16.0/32768.0; 649 | break; 650 | } 651 | } 652 | 653 | 654 | void readAccelData(int16_t * destination) 655 | { 656 | uint8_t rawData[6]; // x/y/z accel register data stored here 657 | readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 658 | destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value 659 | destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; 660 | destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; 661 | } 662 | 663 | 664 | void readGyroData(int16_t * destination) 665 | { 666 | uint8_t rawData[6]; // x/y/z gyro register data stored here 667 | readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 668 | destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value 669 | destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ; 670 | destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ; 671 | } 672 | 673 | void readMagData(int16_t * destination) 674 | { 675 | uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition 676 | if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set 677 | readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array 678 | uint8_t c = rawData[6]; // End data read by reading ST2 register 679 | if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data 680 | destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value 681 | destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; // Data stored as little Endian 682 | destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; 683 | } 684 | } 685 | } 686 | 687 | int16_t readTempData() 688 | { 689 | uint8_t rawData[2]; // x/y/z gyro register data stored here 690 | readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 691 | return ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a 16-bit value 692 | } 693 | 694 | void initAK8963(float * destination) 695 | { 696 | // First extract the factory calibration for each magnetometer axis 697 | uint8_t rawData[3]; // x/y/z gyro calibration data stored here 698 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 699 | delay(10); 700 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode 701 | delay(10); 702 | readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values 703 | destination[0] = (float)(rawData[0] - 128)/256. + 1.; // Return x-axis sensitivity adjustment values, etc. 704 | destination[1] = (float)(rawData[1] - 128)/256. + 1.; 705 | destination[2] = (float)(rawData[2] - 128)/256. + 1.; 706 | writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer 707 | delay(10); 708 | // Configure the magnetometer for continuous read and highest resolution 709 | // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register, 710 | // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates 711 | writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR 712 | delay(10); 713 | } 714 | 715 | 716 | void initMPU9250() 717 | { 718 | // wake up device 719 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 720 | delay(100); // Wait for all registers to reset 721 | 722 | // get stable time source 723 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Auto select clock source to be PLL gyroscope reference if ready else 724 | delay(200); 725 | 726 | // Configure Gyro and Thermometer 727 | // Disable FSYNC and set thermometer and gyro bandwidth to 41 and 42 Hz, respectively; 728 | // minimum delay time for this setting is 5.9 ms, which means sensor fusion update rates cannot 729 | // be higher than 1 / 0.0059 = 170 Hz 730 | // DLPF_CFG = bits 2:0 = 011; this limits the sample rate to 1000 Hz for both 731 | // With the MPU9250, it is possible to get gyro sample rates of 32 kHz (!), 8 kHz, or 1 kHz 732 | writeByte(MPU9250_ADDRESS, CONFIG, 0x03); 733 | 734 | // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 735 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; a rate consistent with the filter update rate 736 | // determined inset in CONFIG above 737 | 738 | // Set gyroscope full scale range 739 | // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 740 | uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG); 741 | // writeRegister(GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 742 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x02); // Clear Fchoice bits [1:0] 743 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 744 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 745 | // writeRegister(GYRO_CONFIG, c | 0x00); // Set Fchoice for the gyro to 11 by writing its inverse to bits 1:0 of GYRO_CONFIG 746 | 747 | // Set accelerometer full-scale range configuration 748 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG); 749 | // writeRegister(ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 750 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 751 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 752 | 753 | // Set accelerometer sample rate configuration 754 | // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for 755 | // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz 756 | c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2); 757 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0]) 758 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz 759 | 760 | // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, 761 | // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting 762 | 763 | // Configure Interrupts and Bypass Enable 764 | // Set interrupt pin active high, push-pull, hold interrupt pin level HIGH until interrupt cleared, 765 | // clear on read of INT_STATUS, and enable I2C_BYPASS_EN so additional chips 766 | // can join the I2C bus and all can be controlled by the Arduino as master 767 | writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22); 768 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 769 | delay(100); 770 | } 771 | 772 | 773 | // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 774 | // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 775 | void calibrateMPU9250(float * dest1, float * dest2) 776 | { 777 | uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 778 | uint16_t ii, packet_count, fifo_count; 779 | int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 780 | 781 | // reset device 782 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 783 | delay(100); 784 | 785 | // get stable time source; Auto select clock source to be PLL gyroscope reference if ready 786 | // else use the internal oscillator, bits 2:0 = 001 787 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); 788 | writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00); 789 | delay(200); 790 | 791 | // Configure device for bias calculation 792 | writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 793 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 794 | writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 795 | writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 796 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 797 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 798 | delay(15); 799 | 800 | // Configure MPU6050 gyro and accelerometer for bias calculation 801 | writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 802 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 803 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 804 | writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 805 | 806 | uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 807 | uint16_t accelsensitivity = 16384; // = 16384 LSB/g 808 | 809 | // Configure FIFO to capture accelerometer and gyro data for bias calculation 810 | writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 811 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9150) 812 | delay(40); // accumulate 40 samples in 40 milliseconds = 480 bytes 813 | 814 | // At end of sample accumulation, turn off FIFO sensor read 815 | writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 816 | readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 817 | fifo_count = ((uint16_t)data[0] << 8) | data[1]; 818 | packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 819 | 820 | for (ii = 0; ii < packet_count; ii++) { 821 | int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 822 | readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 823 | accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 824 | accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 825 | accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 826 | gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 827 | gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 828 | gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 829 | 830 | accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 831 | accel_bias[1] += (int32_t) accel_temp[1]; 832 | accel_bias[2] += (int32_t) accel_temp[2]; 833 | gyro_bias[0] += (int32_t) gyro_temp[0]; 834 | gyro_bias[1] += (int32_t) gyro_temp[1]; 835 | gyro_bias[2] += (int32_t) gyro_temp[2]; 836 | 837 | } 838 | accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 839 | accel_bias[1] /= (int32_t) packet_count; 840 | accel_bias[2] /= (int32_t) packet_count; 841 | gyro_bias[0] /= (int32_t) packet_count; 842 | gyro_bias[1] /= (int32_t) packet_count; 843 | gyro_bias[2] /= (int32_t) packet_count; 844 | 845 | if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 846 | else {accel_bias[2] += (int32_t) accelsensitivity;} 847 | 848 | // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 849 | 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 850 | data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 851 | data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 852 | data[3] = (-gyro_bias[1]/4) & 0xFF; 853 | data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 854 | data[5] = (-gyro_bias[2]/4) & 0xFF; 855 | 856 | // Push gyro biases to hardware registers 857 | writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]); 858 | writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]); 859 | writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]); 860 | writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]); 861 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]); 862 | writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]); 863 | 864 | // Output scaled gyro biases for display in the main program 865 | dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; 866 | dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 867 | dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 868 | 869 | // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 870 | // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 871 | // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 872 | // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 873 | // the accelerometer biases calculated above must be divided by 8. 874 | 875 | int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 876 | readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 877 | accel_bias_reg[0] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 878 | readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]); 879 | accel_bias_reg[1] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 880 | readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 881 | accel_bias_reg[2] = (int32_t) (((int16_t)data[0] << 8) | data[1]); 882 | 883 | uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 884 | uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 885 | 886 | for(ii = 0; ii < 3; ii++) { 887 | if((accel_bias_reg[ii] & mask)) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 888 | } 889 | 890 | // Construct total accelerometer bias, including calculated average accelerometer bias from above 891 | accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 892 | accel_bias_reg[1] -= (accel_bias[1]/8); 893 | accel_bias_reg[2] -= (accel_bias[2]/8); 894 | 895 | data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 896 | data[1] = (accel_bias_reg[0]) & 0xFF; 897 | data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 898 | data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 899 | data[3] = (accel_bias_reg[1]) & 0xFF; 900 | data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 901 | data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 902 | data[5] = (accel_bias_reg[2]) & 0xFF; 903 | data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 904 | 905 | // Apparently this is not working for the acceleration biases in the MPU-9250 906 | // Are we handling the temperature correction bit properly? 907 | // Push accelerometer biases to hardware registers 908 | writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]); 909 | writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]); 910 | writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]); 911 | writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]); 912 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]); 913 | writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]); 914 | 915 | // Output scaled accelerometer biases for display in the main program 916 | dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 917 | dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 918 | dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 919 | } 920 | 921 | // Accelerometer and gyroscope self test; check calibration wrt factory settings 922 | void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 923 | { 924 | uint8_t rawData[6] = {0, 0, 0, 0, 0, 0}; 925 | uint8_t selfTest[6]; 926 | int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3]; 927 | float factoryTrim[6]; 928 | uint8_t FS = 0; 929 | 930 | writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz 931 | writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz 932 | writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<