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