Basic program to obtain properly-scaled gyro, accelerometer, and magnetometer data from the MPU-9150 9-axis motion sensor. Nine-axis sensor fusion with Sebastian Madgwick's and Mahony's open-source sensor fusion filters running on an STM32F401RE Nucleo board at 84 MHz achieve sensor fusion filter update rates of ~5000 Hz. Additional info at https://github.com/kriswiner/STM32F401.
Dependencies: ST_401_84MHZ mbed
Diff: MPU9150.h
- Revision:
- 0:39935bb3c1a1
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/MPU9150.h Sun Jun 29 22:48:08 2014 +0000 @@ -0,0 +1,786 @@ +#ifndef MPU9150_H +#define MPU9150_H + +#include "mbed.h" + +// Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device +// Invensense Inc., www.invensense.com +// See also MPU-9150 Register Map and Descriptions, Revision 4.0, RM-MPU-9150A-00, 9/12/2012 for registers not listed in +// above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor +// +//Magnetometer Registers +#define WHO_AM_I_AK8975A 0x00 // should return 0x48 +#define INFO 0x01 +#define AK8975A_ST1 0x02 // data ready status bit 0 +#define AK8975A_ADDRESS 0x0C<<1 +#define AK8975A_XOUT_L 0x03 // data +#define AK8975A_XOUT_H 0x04 +#define AK8975A_YOUT_L 0x05 +#define AK8975A_YOUT_H 0x06 +#define AK8975A_ZOUT_L 0x07 +#define AK8975A_ZOUT_H 0x08 +#define AK8975A_ST2 0x09 // Data overflow bit 3 and data read error status bit 2 +#define AK8975A_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0 +#define AK8975A_ASTC 0x0C // Self test control +#define AK8975A_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value +#define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value +#define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value + +#define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD +#define YGOFFS_TC 0x01 +#define ZGOFFS_TC 0x02 +#define X_FINE_GAIN 0x03 // [7:0] fine gain +#define Y_FINE_GAIN 0x04 +#define Z_FINE_GAIN 0x05 +#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer +#define XA_OFFSET_L_TC 0x07 +#define YA_OFFSET_H 0x08 +#define YA_OFFSET_L_TC 0x09 +#define ZA_OFFSET_H 0x0A +#define ZA_OFFSET_L_TC 0x0B +#define SELF_TEST_X 0x0D +#define SELF_TEST_Y 0x0E +#define SELF_TEST_Z 0x0F +#define SELF_TEST_A 0x10 +#define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope, populate with calibration routine +#define XG_OFFS_USRL 0x14 +#define YG_OFFS_USRH 0x15 +#define YG_OFFS_USRL 0x16 +#define ZG_OFFS_USRH 0x17 +#define ZG_OFFS_USRL 0x18 +#define SMPLRT_DIV 0x19 +#define CONFIG 0x1A +#define GYRO_CONFIG 0x1B +#define ACCEL_CONFIG 0x1C +#define FF_THR 0x1D // Free-fall +#define FF_DUR 0x1E // Free-fall +#define MOT_THR 0x1F // Motion detection threshold bits [7:0] +#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms +#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] +#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms +#define FIFO_EN 0x23 +#define I2C_MST_CTRL 0x24 +#define I2C_SLV0_ADDR 0x25 +#define I2C_SLV0_REG 0x26 +#define I2C_SLV0_CTRL 0x27 +#define I2C_SLV1_ADDR 0x28 +#define I2C_SLV1_REG 0x29 +#define I2C_SLV1_CTRL 0x2A +#define I2C_SLV2_ADDR 0x2B +#define I2C_SLV2_REG 0x2C +#define I2C_SLV2_CTRL 0x2D +#define I2C_SLV3_ADDR 0x2E +#define I2C_SLV3_REG 0x2F +#define I2C_SLV3_CTRL 0x30 +#define I2C_SLV4_ADDR 0x31 +#define I2C_SLV4_REG 0x32 +#define I2C_SLV4_DO 0x33 +#define I2C_SLV4_CTRL 0x34 +#define I2C_SLV4_DI 0x35 +#define I2C_MST_STATUS 0x36 +#define INT_PIN_CFG 0x37 +#define INT_ENABLE 0x38 +#define DMP_INT_STATUS 0x39 // Check DMP interrupt +#define INT_STATUS 0x3A +#define ACCEL_XOUT_H 0x3B +#define ACCEL_XOUT_L 0x3C +#define ACCEL_YOUT_H 0x3D +#define ACCEL_YOUT_L 0x3E +#define ACCEL_ZOUT_H 0x3F +#define ACCEL_ZOUT_L 0x40 +#define TEMP_OUT_H 0x41 +#define TEMP_OUT_L 0x42 +#define GYRO_XOUT_H 0x43 +#define GYRO_XOUT_L 0x44 +#define GYRO_YOUT_H 0x45 +#define GYRO_YOUT_L 0x46 +#define GYRO_ZOUT_H 0x47 +#define GYRO_ZOUT_L 0x48 +#define EXT_SENS_DATA_00 0x49 +#define EXT_SENS_DATA_01 0x4A +#define EXT_SENS_DATA_02 0x4B +#define EXT_SENS_DATA_03 0x4C +#define EXT_SENS_DATA_04 0x4D +#define EXT_SENS_DATA_05 0x4E +#define EXT_SENS_DATA_06 0x4F +#define EXT_SENS_DATA_07 0x50 +#define EXT_SENS_DATA_08 0x51 +#define EXT_SENS_DATA_09 0x52 +#define EXT_SENS_DATA_10 0x53 +#define EXT_SENS_DATA_11 0x54 +#define EXT_SENS_DATA_12 0x55 +#define EXT_SENS_DATA_13 0x56 +#define EXT_SENS_DATA_14 0x57 +#define EXT_SENS_DATA_15 0x58 +#define EXT_SENS_DATA_16 0x59 +#define EXT_SENS_DATA_17 0x5A +#define EXT_SENS_DATA_18 0x5B +#define EXT_SENS_DATA_19 0x5C +#define EXT_SENS_DATA_20 0x5D +#define EXT_SENS_DATA_21 0x5E +#define EXT_SENS_DATA_22 0x5F +#define EXT_SENS_DATA_23 0x60 +#define MOT_DETECT_STATUS 0x61 +#define I2C_SLV0_DO 0x63 +#define I2C_SLV1_DO 0x64 +#define I2C_SLV2_DO 0x65 +#define I2C_SLV3_DO 0x66 +#define I2C_MST_DELAY_CTRL 0x67 +#define SIGNAL_PATH_RESET 0x68 +#define MOT_DETECT_CTRL 0x69 +#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP +#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode +#define PWR_MGMT_2 0x6C +#define DMP_BANK 0x6D // Activates a specific bank in the DMP +#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank +#define DMP_REG 0x6F // Register in DMP from which to read or to which to write +#define DMP_REG_1 0x70 +#define DMP_REG_2 0x71 +#define FIFO_COUNTH 0x72 +#define FIFO_COUNTL 0x73 +#define FIFO_R_W 0x74 +#define WHO_AM_I_MPU9150 0x75 // Should return 0x68 + + +// Using the GY-9150 breakout board, ADO is set to 0 +// Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 +// mbed uses the eight-bit device address, so shift seven-bit addresses left by one! +#define ADO 0 +#if ADO +#define MPU9150_ADDRESS 0x69<<1 // Device address when ADO = 1 +#else +#define MPU9150_ADDRESS 0x68<<1 // Device address when ADO = 0 +#endif + +// Set initial input parameters +enum Ascale { + AFS_2G = 0, + AFS_4G, + AFS_8G, + AFS_16G +}; + +enum Gscale { + GFS_250DPS = 0, + GFS_500DPS, + GFS_1000DPS, + GFS_2000DPS +}; + +uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G +uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS +float aRes, gRes, mRes; // scale resolutions per LSB for the sensors + +//Set up I2C, (SDA,SCL) +I2C i2c(I2C_SDA, I2C_SCL); + +DigitalOut myled(LED1); + +// Pin definitions +int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins + +int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output +int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output +int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output +float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias +float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer +float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values +int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius +float temperature; +float SelfTest[6]; + +int delt_t = 0; // used to control display output rate +int count = 0; // used to control display output rate + +// parameters for 6 DoF sensor fusion calculations +float PI = 3.14159265358979323846f; +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 +float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta +float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) +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 +#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 +#define Ki 0.0f + +float pitch, yaw, roll; +float deltat = 0.0f; // integration interval for both filter schemes +int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval +float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion +float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method + +class MPU9150 { + + protected: + + public: + //=================================================================================================================== +//====== Set of useful function to access acceleratio, gyroscope, and temperature data +//=================================================================================================================== + + void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) +{ + char data_write[2]; + data_write[0] = subAddress; + data_write[1] = data; + i2c.write(address, data_write, 2, 0); +} + + char readByte(uint8_t address, uint8_t subAddress) +{ + char data[1]; // `data` will store the register data + char data_write[1]; + data_write[0] = subAddress; + i2c.write(address, data_write, 1, 1); // no stop + i2c.read(address, data, 1, 0); + return data[0]; +} + + void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) +{ + char data[14]; + char data_write[1]; + data_write[0] = subAddress; + i2c.write(address, data_write, 1, 1); // no stop + i2c.read(address, data, count, 0); + for(int ii = 0; ii < count; ii++) { + dest[ii] = data[ii]; + } +} + + +void getGres() { + switch (Gscale) + { + // Possible gyro scales (and their register bit settings) are: + // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). + // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: + case GFS_250DPS: + gRes = 250.0/32768.0; + break; + case GFS_500DPS: + gRes = 500.0/32768.0; + break; + case GFS_1000DPS: + gRes = 1000.0/32768.0; + break; + case GFS_2000DPS: + gRes = 2000.0/32768.0; + break; + } +} + + +void getAres() { + switch (Ascale) + { + // Possible accelerometer scales (and their register bit settings) are: + // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). + // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: + case AFS_2G: + aRes = 2.0/32768.0; + break; + case AFS_4G: + aRes = 4.0/32768.0; + break; + case AFS_8G: + aRes = 8.0/32768.0; + break; + case AFS_16G: + aRes = 16.0/32768.0; + break; + } +} + + +void readAccelData(int16_t * destination) +{ + uint8_t rawData[6]; // x/y/z accel register data stored here + readBytes(MPU9150_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array + destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value + destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; + destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; +} + +void readGyroData(int16_t * destination) +{ + uint8_t rawData[6]; // x/y/z gyro register data stored here + readBytes(MPU9150_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array + destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value + destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; + destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; +} + +void readMagData(int16_t * destination) +{ + uint8_t rawData[6]; // x/y/z gyro register data stored here + writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x01); // toggle enable data read from magnetometer, no continuous read mode! + wait(0.01); + // Only accept a new magnetometer data read if the data ready bit is set and + // if there are no sensor overflow or data read errors + if(readByte(AK8975A_ADDRESS, AK8975A_ST1) & 0x01) { // wait for magnetometer data ready bit to be set + readBytes(AK8975A_ADDRESS, AK8975A_XOUT_L, 6, &rawData[0]); // Read the six raw data registers sequentially into data array + destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value + destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; + destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ; + } +} + +void initAK8975A(float * destination) +{ + uint8_t rawData[3]; // x/y/z gyro register data stored here + writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x00); // Power down + wait(0.01); + writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x0F); // Enter Fuse ROM access mode + wait(0.01); + readBytes(AK8975A_ADDRESS, AK8975A_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values + destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values + destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f; + destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f; +} + +int16_t readTempData() +{ + uint8_t rawData[2]; // x/y/z gyro register data stored here + readBytes(MPU9150_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array + return ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a 16-bit value +} + +void resetMPU9150() { + // reset device + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device + wait(0.1); + } + + + +void initMPU9150() +{ + // Initialize MPU9150 device + // wake up device + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors + wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt + + // get stable time source + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 + + // Configure Gyro and Accelerometer + // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; + // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both + // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate + writeByte(MPU9150_ADDRESS, CONFIG, 0x03); + + // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) + writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above + + // Set gyroscope full scale range + // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 + uint8_t c = readByte(MPU9150_ADDRESS, GYRO_CONFIG); + writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] + writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] + writeByte(MPU9150_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro + + // Set accelerometer configuration + c = readByte(MPU9150_ADDRESS, ACCEL_CONFIG); + writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] + writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] + writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer + + // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates, + // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting + + // Configure Interrupts and Bypass Enable + // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips + // can join the I2C bus and all can be controlled by the Arduino as master + writeByte(MPU9150_ADDRESS, INT_PIN_CFG, 0x22); + writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt +} + +// Function which accumulates gyro and accelerometer data after device initialization. It calculates the average +// of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. +void calibrateMPU9150(float * dest1, float * dest2) +{ + uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data + uint16_t ii, packet_count, fifo_count; + int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; + +// reset device, reset all registers, clear gyro and accelerometer bias registers + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device + wait(0.1); + +// get stable time source +// Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x01); + writeByte(MPU9150_ADDRESS, PWR_MGMT_2, 0x00); + wait(0.2); + +// Configure device for bias calculation + writeByte(MPU9150_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts + writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00); // Disable FIFO + writeByte(MPU9150_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source + writeByte(MPU9150_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master + writeByte(MPU9150_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes + writeByte(MPU9150_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP + wait(0.015); + +// Configure MPU9150 gyro and accelerometer for bias calculation + writeByte(MPU9150_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz + writeByte(MPU9150_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz + writeByte(MPU9150_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity + writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity + + uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec + uint16_t accelsensitivity = 16384; // = 16384 LSB/g + +// Configure FIFO to capture accelerometer and gyro data for bias calculation + writeByte(MPU9150_ADDRESS, USER_CTRL, 0x40); // Enable FIFO + writeByte(MPU9150_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU9150) + wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes + +// At end of sample accumulation, turn off FIFO sensor read + writeByte(MPU9150_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO + readBytes(MPU9150_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count + fifo_count = ((uint16_t)data[0] << 8) | data[1]; + packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging + + for (ii = 0; ii < packet_count; ii++) { + int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; + readBytes(MPU9150_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging + accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO + accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; + accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; + gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; + gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; + gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; + + accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases + accel_bias[1] += (int32_t) accel_temp[1]; + accel_bias[2] += (int32_t) accel_temp[2]; + gyro_bias[0] += (int32_t) gyro_temp[0]; + gyro_bias[1] += (int32_t) gyro_temp[1]; + gyro_bias[2] += (int32_t) gyro_temp[2]; + +} + accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases + accel_bias[1] /= (int32_t) packet_count; + accel_bias[2] /= (int32_t) packet_count; + gyro_bias[0] /= (int32_t) packet_count; + gyro_bias[1] /= (int32_t) packet_count; + gyro_bias[2] /= (int32_t) packet_count; + + if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation + else {accel_bias[2] += (int32_t) accelsensitivity;} + +// Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup + 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 + data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases + data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; + data[3] = (-gyro_bias[1]/4) & 0xFF; + data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; + data[5] = (-gyro_bias[2]/4) & 0xFF; + +/// Push gyro biases to hardware registers + writeByte(MPU9150_ADDRESS, XG_OFFS_USRH, data[0]); + writeByte(MPU9150_ADDRESS, XG_OFFS_USRL, data[1]); + writeByte(MPU9150_ADDRESS, YG_OFFS_USRH, data[2]); + writeByte(MPU9150_ADDRESS, YG_OFFS_USRL, data[3]); + writeByte(MPU9150_ADDRESS, ZG_OFFS_USRH, data[4]); + writeByte(MPU9150_ADDRESS, ZG_OFFS_USRL, data[5]); + + dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction + dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; + dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; + +// Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain +// factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold +// non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature +// compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that +// the accelerometer biases calculated above must be divided by 8. + + int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases + readBytes(MPU9150_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values + accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + readBytes(MPU9150_ADDRESS, YA_OFFSET_H, 2, &data[0]); + accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + readBytes(MPU9150_ADDRESS, ZA_OFFSET_H, 2, &data[0]); + accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + + uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers + uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis + + for(ii = 0; ii < 3; ii++) { + if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit + } + + // Construct total accelerometer bias, including calculated average accelerometer bias from above + accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) + accel_bias_reg[1] -= (accel_bias[1]/8); + accel_bias_reg[2] -= (accel_bias[2]/8); + + data[0] = (accel_bias_reg[0] >> 8) & 0xFF; + data[1] = (accel_bias_reg[0]) & 0xFF; + data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers + data[2] = (accel_bias_reg[1] >> 8) & 0xFF; + data[3] = (accel_bias_reg[1]) & 0xFF; + data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers + data[4] = (accel_bias_reg[2] >> 8) & 0xFF; + data[5] = (accel_bias_reg[2]) & 0xFF; + data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers + +// Apparently this is not working for the acceleration biases in the MPU-9250 +// Are we handling the temperature correction bit properly? +// Push accelerometer biases to hardware registers + writeByte(MPU9150_ADDRESS, XA_OFFSET_H, data[0]); + writeByte(MPU9150_ADDRESS, XA_OFFSET_L_TC, data[1]); + writeByte(MPU9150_ADDRESS, YA_OFFSET_H, data[2]); + writeByte(MPU9150_ADDRESS, YA_OFFSET_L_TC, data[3]); + writeByte(MPU9150_ADDRESS, ZA_OFFSET_H, data[4]); + writeByte(MPU9150_ADDRESS, ZA_OFFSET_L_TC, data[5]); + +// Output scaled accelerometer biases for manual subtraction in the main program + dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; + dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; + dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; +} + + +// Accelerometer and gyroscope self test; check calibration wrt factory settings +void MPU9150SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass +{ + uint8_t rawData[4] = {0, 0, 0, 0}; + uint8_t selfTest[6]; + float factoryTrim[6]; + + // Configure the accelerometer for self-test + writeByte(MPU9150_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g + writeByte(MPU9150_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s + wait(0.25); // Delay a while to let the device execute the self-test + rawData[0] = readByte(MPU9150_ADDRESS, SELF_TEST_X); // X-axis self-test results + rawData[1] = readByte(MPU9150_ADDRESS, SELF_TEST_Y); // Y-axis self-test results + rawData[2] = readByte(MPU9150_ADDRESS, SELF_TEST_Z); // Z-axis self-test results + rawData[3] = readByte(MPU9150_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results + // Extract the acceleration test results first + selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer + selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer + selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer + // Extract the gyration test results first + selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer + selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer + selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer + // Process results to allow final comparison with factory set values + factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation + factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation + factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation + factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation + factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation + factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation + + // Output self-test results and factory trim calculation if desired + // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); + // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); + // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); + // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); + + // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response + // To get to percent, must multiply by 100 and subtract result from 100 + for (int i = 0; i < 6; i++) { + destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences + } + +} + + + +// Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" +// (see http://www.x-io.co.uk/category/open-source/ for examples and more details) +// which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute +// device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. +// The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms +// but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! + void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) + { + float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability + float norm; + float hx, hy, _2bx, _2bz; + float s1, s2, s3, s4; + float qDot1, qDot2, qDot3, qDot4; + + // Auxiliary variables to avoid repeated arithmetic + float _2q1mx; + float _2q1my; + float _2q1mz; + float _2q2mx; + float _4bx; + float _4bz; + float _2q1 = 2.0f * q1; + float _2q2 = 2.0f * q2; + float _2q3 = 2.0f * q3; + float _2q4 = 2.0f * q4; + float _2q1q3 = 2.0f * q1 * q3; + float _2q3q4 = 2.0f * q3 * q4; + float q1q1 = q1 * q1; + float q1q2 = q1 * q2; + float q1q3 = q1 * q3; + float q1q4 = q1 * q4; + float q2q2 = q2 * q2; + float q2q3 = q2 * q3; + float q2q4 = q2 * q4; + float q3q3 = q3 * q3; + float q3q4 = q3 * q4; + float q4q4 = q4 * q4; + + // Normalise accelerometer measurement + norm = sqrt(ax * ax + ay * ay + az * az); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f/norm; + ax *= norm; + ay *= norm; + az *= norm; + + // Normalise magnetometer measurement + norm = sqrt(mx * mx + my * my + mz * mz); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f/norm; + mx *= norm; + my *= norm; + mz *= norm; + + // Reference direction of Earth's magnetic field + _2q1mx = 2.0f * q1 * mx; + _2q1my = 2.0f * q1 * my; + _2q1mz = 2.0f * q1 * mz; + _2q2mx = 2.0f * q2 * mx; + hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; + hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; + _2bx = sqrt(hx * hx + hy * hy); + _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; + _4bx = 2.0f * _2bx; + _4bz = 2.0f * _2bz; + + // Gradient decent algorithm corrective step + 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); + 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); + 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); + 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); + norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude + norm = 1.0f/norm; + s1 *= norm; + s2 *= norm; + s3 *= norm; + s4 *= norm; + + // Compute rate of change of quaternion + qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; + qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; + qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; + qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; + + // Integrate to yield quaternion + q1 += qDot1 * deltat; + q2 += qDot2 * deltat; + q3 += qDot3 * deltat; + q4 += qDot4 * deltat; + norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion + norm = 1.0f/norm; + q[0] = q1 * norm; + q[1] = q2 * norm; + q[2] = q3 * norm; + q[3] = q4 * norm; + + } + + + + // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and + // measured ones. + void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) + { + float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability + float norm; + float hx, hy, bx, bz; + float vx, vy, vz, wx, wy, wz; + float ex, ey, ez; + float pa, pb, pc; + + // Auxiliary variables to avoid repeated arithmetic + float q1q1 = q1 * q1; + float q1q2 = q1 * q2; + float q1q3 = q1 * q3; + float q1q4 = q1 * q4; + float q2q2 = q2 * q2; + float q2q3 = q2 * q3; + float q2q4 = q2 * q4; + float q3q3 = q3 * q3; + float q3q4 = q3 * q4; + float q4q4 = q4 * q4; + + // Normalise accelerometer measurement + norm = sqrt(ax * ax + ay * ay + az * az); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f / norm; // use reciprocal for division + ax *= norm; + ay *= norm; + az *= norm; + + // Normalise magnetometer measurement + norm = sqrt(mx * mx + my * my + mz * mz); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f / norm; // use reciprocal for division + mx *= norm; + my *= norm; + mz *= norm; + + // Reference direction of Earth's magnetic field + hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3); + hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2); + bx = sqrt((hx * hx) + (hy * hy)); + bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3); + + // Estimated direction of gravity and magnetic field + vx = 2.0f * (q2q4 - q1q3); + vy = 2.0f * (q1q2 + q3q4); + vz = q1q1 - q2q2 - q3q3 + q4q4; + wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3); + wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4); + wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3); + + // Error is cross product between estimated direction and measured direction of gravity + ex = (ay * vz - az * vy) + (my * wz - mz * wy); + ey = (az * vx - ax * vz) + (mz * wx - mx * wz); + ez = (ax * vy - ay * vx) + (mx * wy - my * wx); + if (Ki > 0.0f) + { + eInt[0] += ex; // accumulate integral error + eInt[1] += ey; + eInt[2] += ez; + } + else + { + eInt[0] = 0.0f; // prevent integral wind up + eInt[1] = 0.0f; + eInt[2] = 0.0f; + } + + // Apply feedback terms + gx = gx + Kp * ex + Ki * eInt[0]; + gy = gy + Kp * ey + Ki * eInt[1]; + gz = gz + Kp * ez + Ki * eInt[2]; + + // Integrate rate of change of quaternion + pa = q2; + pb = q3; + pc = q4; + q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat); + q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat); + q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat); + q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat); + + // Normalise quaternion + norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); + norm = 1.0f / norm; + q[0] = q1 * norm; + q[1] = q2 * norm; + q[2] = q3 * norm; + q[3] = q4 * norm; + + } + }; +#endif \ No newline at end of file