fin

Dependents:   A5_jordanbeason

Committer:
jbeason3
Date:
Tue Nov 19 04:30:54 2019 +0000
Revision:
0:a1a586e251c8
fin;

Who changed what in which revision?

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