I2C pin numbers are changed in this library according to our custom design.

Dependents:   nRF52832_MPU9250

Committer:
sanjay_ingale
Date:
Thu Aug 17 07:54:41 2017 +0000
Revision:
0:8a0a9422787d
I2C pin numbers are changed according to our custom design

Who changed what in which revision?

UserRevisionLine numberNew contents of line
sanjay_ingale 0:8a0a9422787d 1 #ifndef MPU9250_H
sanjay_ingale 0:8a0a9422787d 2 #define MPU9250_H
sanjay_ingale 0:8a0a9422787d 3
sanjay_ingale 0:8a0a9422787d 4 #include "mbed.h"
sanjay_ingale 0:8a0a9422787d 5 #include "math.h"
sanjay_ingale 0:8a0a9422787d 6
sanjay_ingale 0:8a0a9422787d 7 // See also MPU-9250 Register Map and Descriptions, Revision 4.0, RM-MPU-9250A-00, Rev. 1.4, 9/9/2013 for registers not listed in
sanjay_ingale 0:8a0a9422787d 8 // above document; the MPU9250 and MPU9150 are virtually identical but the latter has a different register map
sanjay_ingale 0:8a0a9422787d 9 //
sanjay_ingale 0:8a0a9422787d 10 //Magnetometer Registers
sanjay_ingale 0:8a0a9422787d 11 #define AK8963_ADDRESS 0x0C<<1
sanjay_ingale 0:8a0a9422787d 12 #define WHO_AM_I_AK8963 0x00 // should return 0x48
sanjay_ingale 0:8a0a9422787d 13 #define INFO 0x01
sanjay_ingale 0:8a0a9422787d 14 #define AK8963_ST1 0x02 // data ready status bit 0
sanjay_ingale 0:8a0a9422787d 15 #define AK8963_XOUT_L 0x03 // data
sanjay_ingale 0:8a0a9422787d 16 #define AK8963_XOUT_H 0x04
sanjay_ingale 0:8a0a9422787d 17 #define AK8963_YOUT_L 0x05
sanjay_ingale 0:8a0a9422787d 18 #define AK8963_YOUT_H 0x06
sanjay_ingale 0:8a0a9422787d 19 #define AK8963_ZOUT_L 0x07
sanjay_ingale 0:8a0a9422787d 20 #define AK8963_ZOUT_H 0x08
sanjay_ingale 0:8a0a9422787d 21 #define AK8963_ST2 0x09 // Data overflow bit 3 and data read error status bit 2
sanjay_ingale 0:8a0a9422787d 22 #define AK8963_CNTL 0x0A // Power down (0000), single-measurement (0001), self-test (1000) and Fuse ROM (1111) modes on bits 3:0
sanjay_ingale 0:8a0a9422787d 23 #define AK8963_ASTC 0x0C // Self test control
sanjay_ingale 0:8a0a9422787d 24 #define AK8963_I2CDIS 0x0F // I2C disable
sanjay_ingale 0:8a0a9422787d 25 #define AK8963_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value
sanjay_ingale 0:8a0a9422787d 26 #define AK8963_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value
sanjay_ingale 0:8a0a9422787d 27 #define AK8963_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value
sanjay_ingale 0:8a0a9422787d 28
sanjay_ingale 0:8a0a9422787d 29 #define SELF_TEST_X_GYRO 0x00
sanjay_ingale 0:8a0a9422787d 30 #define SELF_TEST_Y_GYRO 0x01
sanjay_ingale 0:8a0a9422787d 31 #define SELF_TEST_Z_GYRO 0x02
sanjay_ingale 0:8a0a9422787d 32
sanjay_ingale 0:8a0a9422787d 33 /*#define X_FINE_GAIN 0x03 // [7:0] fine gain
sanjay_ingale 0:8a0a9422787d 34 #define Y_FINE_GAIN 0x04
sanjay_ingale 0:8a0a9422787d 35 #define Z_FINE_GAIN 0x05
sanjay_ingale 0:8a0a9422787d 36 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer
sanjay_ingale 0:8a0a9422787d 37 #define XA_OFFSET_L_TC 0x07
sanjay_ingale 0:8a0a9422787d 38 #define YA_OFFSET_H 0x08
sanjay_ingale 0:8a0a9422787d 39 #define YA_OFFSET_L_TC 0x09
sanjay_ingale 0:8a0a9422787d 40 #define ZA_OFFSET_H 0x0A
sanjay_ingale 0:8a0a9422787d 41 #define ZA_OFFSET_L_TC 0x0B */
sanjay_ingale 0:8a0a9422787d 42
sanjay_ingale 0:8a0a9422787d 43 #define SELF_TEST_X_ACCEL 0x0D
sanjay_ingale 0:8a0a9422787d 44 #define SELF_TEST_Y_ACCEL 0x0E
sanjay_ingale 0:8a0a9422787d 45 #define SELF_TEST_Z_ACCEL 0x0F
sanjay_ingale 0:8a0a9422787d 46
sanjay_ingale 0:8a0a9422787d 47 #define SELF_TEST_A 0x10
sanjay_ingale 0:8a0a9422787d 48
sanjay_ingale 0:8a0a9422787d 49 #define XG_OFFSET_H 0x13 // User-defined trim values for gyroscope
sanjay_ingale 0:8a0a9422787d 50 #define XG_OFFSET_L 0x14
sanjay_ingale 0:8a0a9422787d 51 #define YG_OFFSET_H 0x15
sanjay_ingale 0:8a0a9422787d 52 #define YG_OFFSET_L 0x16
sanjay_ingale 0:8a0a9422787d 53 #define ZG_OFFSET_H 0x17
sanjay_ingale 0:8a0a9422787d 54 #define ZG_OFFSET_L 0x18
sanjay_ingale 0:8a0a9422787d 55 #define SMPLRT_DIV 0x19
sanjay_ingale 0:8a0a9422787d 56 #define CONFIG 0x1A
sanjay_ingale 0:8a0a9422787d 57 #define GYRO_CONFIG 0x1B
sanjay_ingale 0:8a0a9422787d 58 #define ACCEL_CONFIG 0x1C
sanjay_ingale 0:8a0a9422787d 59 #define ACCEL_CONFIG2 0x1D
sanjay_ingale 0:8a0a9422787d 60 #define LP_ACCEL_ODR 0x1E
sanjay_ingale 0:8a0a9422787d 61 #define WOM_THR 0x1F
sanjay_ingale 0:8a0a9422787d 62
sanjay_ingale 0:8a0a9422787d 63 #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms
sanjay_ingale 0:8a0a9422787d 64 #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0]
sanjay_ingale 0:8a0a9422787d 65 #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms
sanjay_ingale 0:8a0a9422787d 66
sanjay_ingale 0:8a0a9422787d 67 #define FIFO_EN 0x23
sanjay_ingale 0:8a0a9422787d 68 #define I2C_MST_CTRL 0x24
sanjay_ingale 0:8a0a9422787d 69 #define I2C_SLV0_ADDR 0x25
sanjay_ingale 0:8a0a9422787d 70 #define I2C_SLV0_REG 0x26
sanjay_ingale 0:8a0a9422787d 71 #define I2C_SLV0_CTRL 0x27
sanjay_ingale 0:8a0a9422787d 72 #define I2C_SLV1_ADDR 0x28
sanjay_ingale 0:8a0a9422787d 73 #define I2C_SLV1_REG 0x29
sanjay_ingale 0:8a0a9422787d 74 #define I2C_SLV1_CTRL 0x2A
sanjay_ingale 0:8a0a9422787d 75 #define I2C_SLV2_ADDR 0x2B
sanjay_ingale 0:8a0a9422787d 76 #define I2C_SLV2_REG 0x2C
sanjay_ingale 0:8a0a9422787d 77 #define I2C_SLV2_CTRL 0x2D
sanjay_ingale 0:8a0a9422787d 78 #define I2C_SLV3_ADDR 0x2E
sanjay_ingale 0:8a0a9422787d 79 #define I2C_SLV3_REG 0x2F
sanjay_ingale 0:8a0a9422787d 80 #define I2C_SLV3_CTRL 0x30
sanjay_ingale 0:8a0a9422787d 81 #define I2C_SLV4_ADDR 0x31
sanjay_ingale 0:8a0a9422787d 82 #define I2C_SLV4_REG 0x32
sanjay_ingale 0:8a0a9422787d 83 #define I2C_SLV4_DO 0x33
sanjay_ingale 0:8a0a9422787d 84 #define I2C_SLV4_CTRL 0x34
sanjay_ingale 0:8a0a9422787d 85 #define I2C_SLV4_DI 0x35
sanjay_ingale 0:8a0a9422787d 86 #define I2C_MST_STATUS 0x36
sanjay_ingale 0:8a0a9422787d 87 #define INT_PIN_CFG 0x37
sanjay_ingale 0:8a0a9422787d 88 #define INT_ENABLE 0x38
sanjay_ingale 0:8a0a9422787d 89 #define DMP_INT_STATUS 0x39 // Check DMP interrupt
sanjay_ingale 0:8a0a9422787d 90 #define INT_STATUS 0x3A
sanjay_ingale 0:8a0a9422787d 91 #define ACCEL_XOUT_H 0x3B
sanjay_ingale 0:8a0a9422787d 92 #define ACCEL_XOUT_L 0x3C
sanjay_ingale 0:8a0a9422787d 93 #define ACCEL_YOUT_H 0x3D
sanjay_ingale 0:8a0a9422787d 94 #define ACCEL_YOUT_L 0x3E
sanjay_ingale 0:8a0a9422787d 95 #define ACCEL_ZOUT_H 0x3F
sanjay_ingale 0:8a0a9422787d 96 #define ACCEL_ZOUT_L 0x40
sanjay_ingale 0:8a0a9422787d 97 #define TEMP_OUT_H 0x41
sanjay_ingale 0:8a0a9422787d 98 #define TEMP_OUT_L 0x42
sanjay_ingale 0:8a0a9422787d 99 #define GYRO_XOUT_H 0x43
sanjay_ingale 0:8a0a9422787d 100 #define GYRO_XOUT_L 0x44
sanjay_ingale 0:8a0a9422787d 101 #define GYRO_YOUT_H 0x45
sanjay_ingale 0:8a0a9422787d 102 #define GYRO_YOUT_L 0x46
sanjay_ingale 0:8a0a9422787d 103 #define GYRO_ZOUT_H 0x47
sanjay_ingale 0:8a0a9422787d 104 #define GYRO_ZOUT_L 0x48
sanjay_ingale 0:8a0a9422787d 105 #define EXT_SENS_DATA_00 0x49
sanjay_ingale 0:8a0a9422787d 106 #define EXT_SENS_DATA_01 0x4A
sanjay_ingale 0:8a0a9422787d 107 #define EXT_SENS_DATA_02 0x4B
sanjay_ingale 0:8a0a9422787d 108 #define EXT_SENS_DATA_03 0x4C
sanjay_ingale 0:8a0a9422787d 109 #define EXT_SENS_DATA_04 0x4D
sanjay_ingale 0:8a0a9422787d 110 #define EXT_SENS_DATA_05 0x4E
sanjay_ingale 0:8a0a9422787d 111 #define EXT_SENS_DATA_06 0x4F
sanjay_ingale 0:8a0a9422787d 112 #define EXT_SENS_DATA_07 0x50
sanjay_ingale 0:8a0a9422787d 113 #define EXT_SENS_DATA_08 0x51
sanjay_ingale 0:8a0a9422787d 114 #define EXT_SENS_DATA_09 0x52
sanjay_ingale 0:8a0a9422787d 115 #define EXT_SENS_DATA_10 0x53
sanjay_ingale 0:8a0a9422787d 116 #define EXT_SENS_DATA_11 0x54
sanjay_ingale 0:8a0a9422787d 117 #define EXT_SENS_DATA_12 0x55
sanjay_ingale 0:8a0a9422787d 118 #define EXT_SENS_DATA_13 0x56
sanjay_ingale 0:8a0a9422787d 119 #define EXT_SENS_DATA_14 0x57
sanjay_ingale 0:8a0a9422787d 120 #define EXT_SENS_DATA_15 0x58
sanjay_ingale 0:8a0a9422787d 121 #define EXT_SENS_DATA_16 0x59
sanjay_ingale 0:8a0a9422787d 122 #define EXT_SENS_DATA_17 0x5A
sanjay_ingale 0:8a0a9422787d 123 #define EXT_SENS_DATA_18 0x5B
sanjay_ingale 0:8a0a9422787d 124 #define EXT_SENS_DATA_19 0x5C
sanjay_ingale 0:8a0a9422787d 125 #define EXT_SENS_DATA_20 0x5D
sanjay_ingale 0:8a0a9422787d 126 #define EXT_SENS_DATA_21 0x5E
sanjay_ingale 0:8a0a9422787d 127 #define EXT_SENS_DATA_22 0x5F
sanjay_ingale 0:8a0a9422787d 128 #define EXT_SENS_DATA_23 0x60
sanjay_ingale 0:8a0a9422787d 129 #define MOT_DETECT_STATUS 0x61
sanjay_ingale 0:8a0a9422787d 130 #define I2C_SLV0_DO 0x63
sanjay_ingale 0:8a0a9422787d 131 #define I2C_SLV1_DO 0x64
sanjay_ingale 0:8a0a9422787d 132 #define I2C_SLV2_DO 0x65
sanjay_ingale 0:8a0a9422787d 133 #define I2C_SLV3_DO 0x66
sanjay_ingale 0:8a0a9422787d 134 #define I2C_MST_DELAY_CTRL 0x67
sanjay_ingale 0:8a0a9422787d 135 #define SIGNAL_PATH_RESET 0x68
sanjay_ingale 0:8a0a9422787d 136 #define MOT_DETECT_CTRL 0x69
sanjay_ingale 0:8a0a9422787d 137 #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP
sanjay_ingale 0:8a0a9422787d 138 #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode
sanjay_ingale 0:8a0a9422787d 139 #define PWR_MGMT_2 0x6C
sanjay_ingale 0:8a0a9422787d 140 #define DMP_BANK 0x6D // Activates a specific bank in the DMP
sanjay_ingale 0:8a0a9422787d 141 #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank
sanjay_ingale 0:8a0a9422787d 142 #define DMP_REG 0x6F // Register in DMP from which to read or to which to write
sanjay_ingale 0:8a0a9422787d 143 #define DMP_REG_1 0x70
sanjay_ingale 0:8a0a9422787d 144 #define DMP_REG_2 0x71
sanjay_ingale 0:8a0a9422787d 145 #define FIFO_COUNTH 0x72
sanjay_ingale 0:8a0a9422787d 146 #define FIFO_COUNTL 0x73
sanjay_ingale 0:8a0a9422787d 147 #define FIFO_R_W 0x74
sanjay_ingale 0:8a0a9422787d 148 #define WHO_AM_I_MPU9250 0x75 // Should return 0x71
sanjay_ingale 0:8a0a9422787d 149 #define XA_OFFSET_H 0x77
sanjay_ingale 0:8a0a9422787d 150 #define XA_OFFSET_L 0x78
sanjay_ingale 0:8a0a9422787d 151 #define YA_OFFSET_H 0x7A
sanjay_ingale 0:8a0a9422787d 152 #define YA_OFFSET_L 0x7B
sanjay_ingale 0:8a0a9422787d 153 #define ZA_OFFSET_H 0x7D
sanjay_ingale 0:8a0a9422787d 154 #define ZA_OFFSET_L 0x7E
sanjay_ingale 0:8a0a9422787d 155
sanjay_ingale 0:8a0a9422787d 156 // Using the MSENSR-9250 breakout board, ADO is set to 0
sanjay_ingale 0:8a0a9422787d 157 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
sanjay_ingale 0:8a0a9422787d 158 //mbed uses the eight-bit device address, so shift seven-bit addresses left by one!
sanjay_ingale 0:8a0a9422787d 159 #define ADO 1
sanjay_ingale 0:8a0a9422787d 160 #if ADO
sanjay_ingale 0:8a0a9422787d 161 #define MPU9250_ADDRESS 0x69<<1 // Device address when ADO = 1
sanjay_ingale 0:8a0a9422787d 162 #else
sanjay_ingale 0:8a0a9422787d 163 #define MPU9250_ADDRESS 0x68<<1 // Device address when ADO = 0
sanjay_ingale 0:8a0a9422787d 164 #endif
sanjay_ingale 0:8a0a9422787d 165
sanjay_ingale 0:8a0a9422787d 166 // Set initial input parameters
sanjay_ingale 0:8a0a9422787d 167 enum Ascale {
sanjay_ingale 0:8a0a9422787d 168 AFS_2G = 0,
sanjay_ingale 0:8a0a9422787d 169 AFS_4G,
sanjay_ingale 0:8a0a9422787d 170 AFS_8G,
sanjay_ingale 0:8a0a9422787d 171 AFS_16G
sanjay_ingale 0:8a0a9422787d 172 };
sanjay_ingale 0:8a0a9422787d 173
sanjay_ingale 0:8a0a9422787d 174 enum Gscale {
sanjay_ingale 0:8a0a9422787d 175 GFS_250DPS = 0,
sanjay_ingale 0:8a0a9422787d 176 GFS_500DPS,
sanjay_ingale 0:8a0a9422787d 177 GFS_1000DPS,
sanjay_ingale 0:8a0a9422787d 178 GFS_2000DPS
sanjay_ingale 0:8a0a9422787d 179 };
sanjay_ingale 0:8a0a9422787d 180
sanjay_ingale 0:8a0a9422787d 181 enum Mscale {
sanjay_ingale 0:8a0a9422787d 182 MFS_14BITS = 0, // 0.6 mG per LSB
sanjay_ingale 0:8a0a9422787d 183 MFS_16BITS // 0.15 mG per LSB
sanjay_ingale 0:8a0a9422787d 184 };
sanjay_ingale 0:8a0a9422787d 185
sanjay_ingale 0:8a0a9422787d 186 uint8_t Ascale = AFS_2G; // AFS_2G, AFS_4G, AFS_8G, AFS_16G
sanjay_ingale 0:8a0a9422787d 187 uint8_t Gscale = GFS_250DPS; // GFS_250DPS, GFS_500DPS, GFS_1000DPS, GFS_2000DPS
sanjay_ingale 0:8a0a9422787d 188 uint8_t Mscale = MFS_16BITS; // MFS_14BITS or MFS_16BITS, 14-bit or 16-bit magnetometer resolution
sanjay_ingale 0:8a0a9422787d 189 uint8_t Mmode = 0x06; // Either 8 Hz 0x02) or 100 Hz (0x06) magnetometer data ODR
sanjay_ingale 0:8a0a9422787d 190 float aRes, gRes, mRes; // scale resolutions per LSB for the sensors
sanjay_ingale 0:8a0a9422787d 191
sanjay_ingale 0:8a0a9422787d 192 //Set up I2C, (SDA,SCL)
sanjay_ingale 0:8a0a9422787d 193 //I2C i2c(I2C_SDA, I2C_SCL);
sanjay_ingale 0:8a0a9422787d 194 //I2C i2c(P0_0, P0_1); // nRF51 FC
sanjay_ingale 0:8a0a9422787d 195 //I2C i2c(P0_6, P0_7); // nRF52 QFN dev board
sanjay_ingale 0:8a0a9422787d 196 I2C i2c(P0_30, P0_28); // nRF52 CIAA dev board
sanjay_ingale 0:8a0a9422787d 197
sanjay_ingale 0:8a0a9422787d 198 //DigitalOut myled(P0_19); // mbed kit
sanjay_ingale 0:8a0a9422787d 199 //DigitalOut myled(P0_18); // nRF51822 module
sanjay_ingale 0:8a0a9422787d 200 DigitalOut myled(P0_24); // nRF52832 module
sanjay_ingale 0:8a0a9422787d 201
sanjay_ingale 0:8a0a9422787d 202 // Pin definitions
sanjay_ingale 0:8a0a9422787d 203 bool newData = false;
sanjay_ingale 0:8a0a9422787d 204 bool newMagData = false;
sanjay_ingale 0:8a0a9422787d 205
sanjay_ingale 0:8a0a9422787d 206 int16_t MPU9250Data[7]; // used to read all 14 bytes at once from the MPU9250 accel/gyro
sanjay_ingale 0:8a0a9422787d 207 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
sanjay_ingale 0:8a0a9422787d 208 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
sanjay_ingale 0:8a0a9422787d 209 int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output
sanjay_ingale 0:8a0a9422787d 210 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias
sanjay_ingale 0:8a0a9422787d 211 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}, magBias[3] = {0, 0, 0}, magScale[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
sanjay_ingale 0:8a0a9422787d 212 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
sanjay_ingale 0:8a0a9422787d 213 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius
sanjay_ingale 0:8a0a9422787d 214 float temperature;
sanjay_ingale 0:8a0a9422787d 215 float SelfTest[6];
sanjay_ingale 0:8a0a9422787d 216
sanjay_ingale 0:8a0a9422787d 217 int delt_t = 0; // used to control display output rate
sanjay_ingale 0:8a0a9422787d 218 int count = 0; // used to control display output rate
sanjay_ingale 0:8a0a9422787d 219
sanjay_ingale 0:8a0a9422787d 220 // parameters for 6 DoF sensor fusion calculations
sanjay_ingale 0:8a0a9422787d 221 float PI = 3.14159265358979323846f;
sanjay_ingale 0:8a0a9422787d 222 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
sanjay_ingale 0:8a0a9422787d 223 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
sanjay_ingale 0:8a0a9422787d 224 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
sanjay_ingale 0:8a0a9422787d 225 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
sanjay_ingale 0:8a0a9422787d 226 #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
sanjay_ingale 0:8a0a9422787d 227 #define Ki 0.0f
sanjay_ingale 0:8a0a9422787d 228
sanjay_ingale 0:8a0a9422787d 229 float pitch, yaw, roll;
sanjay_ingale 0:8a0a9422787d 230 float deltat = 0.0f; // integration interval for both filter schemes
sanjay_ingale 0:8a0a9422787d 231 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval
sanjay_ingale 0:8a0a9422787d 232 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
sanjay_ingale 0:8a0a9422787d 233 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
sanjay_ingale 0:8a0a9422787d 234
sanjay_ingale 0:8a0a9422787d 235 class MPU9250 {
sanjay_ingale 0:8a0a9422787d 236
sanjay_ingale 0:8a0a9422787d 237 protected:
sanjay_ingale 0:8a0a9422787d 238
sanjay_ingale 0:8a0a9422787d 239 public:
sanjay_ingale 0:8a0a9422787d 240 //===================================================================================================================
sanjay_ingale 0:8a0a9422787d 241 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
sanjay_ingale 0:8a0a9422787d 242 //===================================================================================================================
sanjay_ingale 0:8a0a9422787d 243
sanjay_ingale 0:8a0a9422787d 244 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
sanjay_ingale 0:8a0a9422787d 245 {
sanjay_ingale 0:8a0a9422787d 246 char data_write[2];
sanjay_ingale 0:8a0a9422787d 247 data_write[0] = subAddress;
sanjay_ingale 0:8a0a9422787d 248 data_write[1] = data;
sanjay_ingale 0:8a0a9422787d 249 i2c.write(address, data_write, 2, 0);
sanjay_ingale 0:8a0a9422787d 250 }
sanjay_ingale 0:8a0a9422787d 251
sanjay_ingale 0:8a0a9422787d 252 char readByte(uint8_t address, uint8_t subAddress)
sanjay_ingale 0:8a0a9422787d 253 {
sanjay_ingale 0:8a0a9422787d 254 char data[1]; // `data` will store the register data
sanjay_ingale 0:8a0a9422787d 255 char data_write[1];
sanjay_ingale 0:8a0a9422787d 256 data_write[0] = subAddress;
sanjay_ingale 0:8a0a9422787d 257 i2c.write(address, data_write, 1, 1); // no stop
sanjay_ingale 0:8a0a9422787d 258 i2c.read(address, data, 1, 0);
sanjay_ingale 0:8a0a9422787d 259 return data[0];
sanjay_ingale 0:8a0a9422787d 260 }
sanjay_ingale 0:8a0a9422787d 261
sanjay_ingale 0:8a0a9422787d 262 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
sanjay_ingale 0:8a0a9422787d 263 {
sanjay_ingale 0:8a0a9422787d 264 char data[14];
sanjay_ingale 0:8a0a9422787d 265 char data_write[1];
sanjay_ingale 0:8a0a9422787d 266 data_write[0] = subAddress;
sanjay_ingale 0:8a0a9422787d 267 i2c.write(address, data_write, 1, 1); // no stop
sanjay_ingale 0:8a0a9422787d 268 i2c.read(address, data, count, 0);
sanjay_ingale 0:8a0a9422787d 269 for(int ii = 0; ii < count; ii++) {
sanjay_ingale 0:8a0a9422787d 270 dest[ii] = data[ii];
sanjay_ingale 0:8a0a9422787d 271 }
sanjay_ingale 0:8a0a9422787d 272 }
sanjay_ingale 0:8a0a9422787d 273
sanjay_ingale 0:8a0a9422787d 274
sanjay_ingale 0:8a0a9422787d 275 void getMres() {
sanjay_ingale 0:8a0a9422787d 276 switch (Mscale)
sanjay_ingale 0:8a0a9422787d 277 {
sanjay_ingale 0:8a0a9422787d 278 // Possible magnetometer scales (and their register bit settings) are:
sanjay_ingale 0:8a0a9422787d 279 // 14 bit resolution (0) and 16 bit resolution (1)
sanjay_ingale 0:8a0a9422787d 280 case MFS_14BITS:
sanjay_ingale 0:8a0a9422787d 281 mRes = 10.0*4912.0/8190.0; // Proper scale to return milliGauss
sanjay_ingale 0:8a0a9422787d 282 break;
sanjay_ingale 0:8a0a9422787d 283 case MFS_16BITS:
sanjay_ingale 0:8a0a9422787d 284 mRes = 10.0*4912.0/32760.0; // Proper scale to return milliGauss
sanjay_ingale 0:8a0a9422787d 285 break;
sanjay_ingale 0:8a0a9422787d 286 }
sanjay_ingale 0:8a0a9422787d 287 }
sanjay_ingale 0:8a0a9422787d 288
sanjay_ingale 0:8a0a9422787d 289
sanjay_ingale 0:8a0a9422787d 290 void getGres() {
sanjay_ingale 0:8a0a9422787d 291 switch (Gscale)
sanjay_ingale 0:8a0a9422787d 292 {
sanjay_ingale 0:8a0a9422787d 293 // Possible gyro scales (and their register bit settings) are:
sanjay_ingale 0:8a0a9422787d 294 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
sanjay_ingale 0:8a0a9422787d 295 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
sanjay_ingale 0:8a0a9422787d 296 case GFS_250DPS:
sanjay_ingale 0:8a0a9422787d 297 gRes = 250.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 298 break;
sanjay_ingale 0:8a0a9422787d 299 case GFS_500DPS:
sanjay_ingale 0:8a0a9422787d 300 gRes = 500.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 301 break;
sanjay_ingale 0:8a0a9422787d 302 case GFS_1000DPS:
sanjay_ingale 0:8a0a9422787d 303 gRes = 1000.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 304 break;
sanjay_ingale 0:8a0a9422787d 305 case GFS_2000DPS:
sanjay_ingale 0:8a0a9422787d 306 gRes = 2000.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 307 break;
sanjay_ingale 0:8a0a9422787d 308 }
sanjay_ingale 0:8a0a9422787d 309 }
sanjay_ingale 0:8a0a9422787d 310
sanjay_ingale 0:8a0a9422787d 311
sanjay_ingale 0:8a0a9422787d 312 void getAres() {
sanjay_ingale 0:8a0a9422787d 313 switch (Ascale)
sanjay_ingale 0:8a0a9422787d 314 {
sanjay_ingale 0:8a0a9422787d 315 // Possible accelerometer scales (and their register bit settings) are:
sanjay_ingale 0:8a0a9422787d 316 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
sanjay_ingale 0:8a0a9422787d 317 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
sanjay_ingale 0:8a0a9422787d 318 case AFS_2G:
sanjay_ingale 0:8a0a9422787d 319 aRes = 2.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 320 break;
sanjay_ingale 0:8a0a9422787d 321 case AFS_4G:
sanjay_ingale 0:8a0a9422787d 322 aRes = 4.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 323 break;
sanjay_ingale 0:8a0a9422787d 324 case AFS_8G:
sanjay_ingale 0:8a0a9422787d 325 aRes = 8.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 326 break;
sanjay_ingale 0:8a0a9422787d 327 case AFS_16G:
sanjay_ingale 0:8a0a9422787d 328 aRes = 16.0f/32768.0f;
sanjay_ingale 0:8a0a9422787d 329 break;
sanjay_ingale 0:8a0a9422787d 330 }
sanjay_ingale 0:8a0a9422787d 331 }
sanjay_ingale 0:8a0a9422787d 332
sanjay_ingale 0:8a0a9422787d 333 void readMPU9250Data(int16_t * destination)
sanjay_ingale 0:8a0a9422787d 334 {
sanjay_ingale 0:8a0a9422787d 335 uint8_t rawData[14]; // x/y/z accel register data stored here
sanjay_ingale 0:8a0a9422787d 336 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 14, &rawData[0]); // Read the 14 raw data registers into data array
sanjay_ingale 0:8a0a9422787d 337 destination[0] = ((int16_t)rawData[0] << 8) | rawData[1] ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 338 destination[1] = ((int16_t)rawData[2] << 8) | rawData[3] ;
sanjay_ingale 0:8a0a9422787d 339 destination[2] = ((int16_t)rawData[4] << 8) | rawData[5] ;
sanjay_ingale 0:8a0a9422787d 340 destination[3] = ((int16_t)rawData[6] << 8) | rawData[7] ;
sanjay_ingale 0:8a0a9422787d 341 destination[4] = ((int16_t)rawData[8] << 8) | rawData[9] ;
sanjay_ingale 0:8a0a9422787d 342 destination[5] = ((int16_t)rawData[10] << 8) | rawData[11] ;
sanjay_ingale 0:8a0a9422787d 343 destination[6] = ((int16_t)rawData[12] << 8) | rawData[13] ;
sanjay_ingale 0:8a0a9422787d 344 }
sanjay_ingale 0:8a0a9422787d 345
sanjay_ingale 0:8a0a9422787d 346 void readAccelData(int16_t * destination)
sanjay_ingale 0:8a0a9422787d 347 {
sanjay_ingale 0:8a0a9422787d 348 uint8_t rawData[6]; // x/y/z accel register data stored here
sanjay_ingale 0:8a0a9422787d 349 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
sanjay_ingale 0:8a0a9422787d 350 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 351 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 352 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 353 }
sanjay_ingale 0:8a0a9422787d 354
sanjay_ingale 0:8a0a9422787d 355 void readGyroData(int16_t * destination)
sanjay_ingale 0:8a0a9422787d 356 {
sanjay_ingale 0:8a0a9422787d 357 uint8_t rawData[6]; // x/y/z gyro register data stored here
sanjay_ingale 0:8a0a9422787d 358 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
sanjay_ingale 0:8a0a9422787d 359 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 360 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 361 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 362 }
sanjay_ingale 0:8a0a9422787d 363
sanjay_ingale 0:8a0a9422787d 364 void readMagData(int16_t * destination)
sanjay_ingale 0:8a0a9422787d 365 {
sanjay_ingale 0:8a0a9422787d 366 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
sanjay_ingale 0:8a0a9422787d 367 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array
sanjay_ingale 0:8a0a9422787d 368 uint8_t c = rawData[6]; // End data read by reading ST2 register
sanjay_ingale 0:8a0a9422787d 369 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
sanjay_ingale 0:8a0a9422787d 370 destination[0] = ((int16_t)rawData[1] << 8) | rawData[0] ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 371 destination[1] = ((int16_t)rawData[3] << 8) | rawData[2] ; // Data stored as little Endian
sanjay_ingale 0:8a0a9422787d 372 destination[2] = ((int16_t)rawData[5] << 8) | rawData[4] ;
sanjay_ingale 0:8a0a9422787d 373 }
sanjay_ingale 0:8a0a9422787d 374 }
sanjay_ingale 0:8a0a9422787d 375
sanjay_ingale 0:8a0a9422787d 376 int16_t readTempData()
sanjay_ingale 0:8a0a9422787d 377 {
sanjay_ingale 0:8a0a9422787d 378 uint8_t rawData[2]; // x/y/z gyro register data stored here
sanjay_ingale 0:8a0a9422787d 379 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
sanjay_ingale 0:8a0a9422787d 380 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value
sanjay_ingale 0:8a0a9422787d 381 }
sanjay_ingale 0:8a0a9422787d 382
sanjay_ingale 0:8a0a9422787d 383
sanjay_ingale 0:8a0a9422787d 384 void resetMPU9250() {
sanjay_ingale 0:8a0a9422787d 385 // reset device
sanjay_ingale 0:8a0a9422787d 386 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
sanjay_ingale 0:8a0a9422787d 387 wait(0.1);
sanjay_ingale 0:8a0a9422787d 388 }
sanjay_ingale 0:8a0a9422787d 389
sanjay_ingale 0:8a0a9422787d 390 void initAK8963(float * destination)
sanjay_ingale 0:8a0a9422787d 391 {
sanjay_ingale 0:8a0a9422787d 392 // First extract the factory calibration for each magnetometer axis
sanjay_ingale 0:8a0a9422787d 393 uint8_t rawData[3] = {0, 0, 0}; // x/y/z gyro calibration data stored here
sanjay_ingale 0:8a0a9422787d 394 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
sanjay_ingale 0:8a0a9422787d 395 wait(0.01);
sanjay_ingale 0:8a0a9422787d 396 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
sanjay_ingale 0:8a0a9422787d 397 wait(0.01);
sanjay_ingale 0:8a0a9422787d 398 // readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
sanjay_ingale 0:8a0a9422787d 399 rawData[0] = readByte(AK8963_ADDRESS, AK8963_ASAX);
sanjay_ingale 0:8a0a9422787d 400 rawData[1] = readByte(AK8963_ADDRESS, AK8963_ASAY);
sanjay_ingale 0:8a0a9422787d 401 rawData[2] = readByte(AK8963_ADDRESS, AK8963_ASAZ);
sanjay_ingale 0:8a0a9422787d 402 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc.
sanjay_ingale 0:8a0a9422787d 403 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
sanjay_ingale 0:8a0a9422787d 404 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
sanjay_ingale 0:8a0a9422787d 405 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
sanjay_ingale 0:8a0a9422787d 406 wait(0.01);
sanjay_ingale 0:8a0a9422787d 407 // Configure the magnetometer for continuous read and highest resolution
sanjay_ingale 0:8a0a9422787d 408 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
sanjay_ingale 0:8a0a9422787d 409 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
sanjay_ingale 0:8a0a9422787d 410 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
sanjay_ingale 0:8a0a9422787d 411 wait(0.01);
sanjay_ingale 0:8a0a9422787d 412 }
sanjay_ingale 0:8a0a9422787d 413
sanjay_ingale 0:8a0a9422787d 414
sanjay_ingale 0:8a0a9422787d 415 void initMPU9250()
sanjay_ingale 0:8a0a9422787d 416 {
sanjay_ingale 0:8a0a9422787d 417 // Initialize MPU9250 device
sanjay_ingale 0:8a0a9422787d 418 // wake up device
sanjay_ingale 0:8a0a9422787d 419 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
sanjay_ingale 0:8a0a9422787d 420 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
sanjay_ingale 0:8a0a9422787d 421
sanjay_ingale 0:8a0a9422787d 422 // get stable time source
sanjay_ingale 0:8a0a9422787d 423 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
sanjay_ingale 0:8a0a9422787d 424
sanjay_ingale 0:8a0a9422787d 425 // Configure Gyro and Accelerometer
sanjay_ingale 0:8a0a9422787d 426 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
sanjay_ingale 0:8a0a9422787d 427 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
sanjay_ingale 0:8a0a9422787d 428 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
sanjay_ingale 0:8a0a9422787d 429 writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
sanjay_ingale 0:8a0a9422787d 430
sanjay_ingale 0:8a0a9422787d 431 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
sanjay_ingale 0:8a0a9422787d 432 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
sanjay_ingale 0:8a0a9422787d 433
sanjay_ingale 0:8a0a9422787d 434 // Set gyroscope full scale range
sanjay_ingale 0:8a0a9422787d 435 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
sanjay_ingale 0:8a0a9422787d 436 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG);
sanjay_ingale 0:8a0a9422787d 437 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
sanjay_ingale 0:8a0a9422787d 438 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
sanjay_ingale 0:8a0a9422787d 439 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
sanjay_ingale 0:8a0a9422787d 440
sanjay_ingale 0:8a0a9422787d 441 // Set accelerometer configuration
sanjay_ingale 0:8a0a9422787d 442 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG);
sanjay_ingale 0:8a0a9422787d 443 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
sanjay_ingale 0:8a0a9422787d 444 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
sanjay_ingale 0:8a0a9422787d 445 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer
sanjay_ingale 0:8a0a9422787d 446
sanjay_ingale 0:8a0a9422787d 447 // Set accelerometer sample rate configuration
sanjay_ingale 0:8a0a9422787d 448 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
sanjay_ingale 0:8a0a9422787d 449 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
sanjay_ingale 0:8a0a9422787d 450 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2);
sanjay_ingale 0:8a0a9422787d 451 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
sanjay_ingale 0:8a0a9422787d 452 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
sanjay_ingale 0:8a0a9422787d 453
sanjay_ingale 0:8a0a9422787d 454 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
sanjay_ingale 0:8a0a9422787d 455 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
sanjay_ingale 0:8a0a9422787d 456
sanjay_ingale 0:8a0a9422787d 457 // Configure Interrupts and Bypass Enable
sanjay_ingale 0:8a0a9422787d 458 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
sanjay_ingale 0:8a0a9422787d 459 // can join the I2C bus and all can be controlled by the Arduino as master
sanjay_ingale 0:8a0a9422787d 460 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x12); // INT is 50 microsecond pulse and any read to clear
sanjay_ingale 0:8a0a9422787d 461 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
sanjay_ingale 0:8a0a9422787d 462 }
sanjay_ingale 0:8a0a9422787d 463
sanjay_ingale 0:8a0a9422787d 464 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
sanjay_ingale 0:8a0a9422787d 465 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
sanjay_ingale 0:8a0a9422787d 466 void calibrateMPU9250(float * dest1, float * dest2)
sanjay_ingale 0:8a0a9422787d 467 {
sanjay_ingale 0:8a0a9422787d 468 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
sanjay_ingale 0:8a0a9422787d 469 uint16_t ii, packet_count, fifo_count;
sanjay_ingale 0:8a0a9422787d 470 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
sanjay_ingale 0:8a0a9422787d 471
sanjay_ingale 0:8a0a9422787d 472 // reset device, reset all registers, clear gyro and accelerometer bias registers
sanjay_ingale 0:8a0a9422787d 473 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
sanjay_ingale 0:8a0a9422787d 474 wait(0.1);
sanjay_ingale 0:8a0a9422787d 475
sanjay_ingale 0:8a0a9422787d 476 // get stable time source
sanjay_ingale 0:8a0a9422787d 477 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
sanjay_ingale 0:8a0a9422787d 478 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
sanjay_ingale 0:8a0a9422787d 479 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
sanjay_ingale 0:8a0a9422787d 480 wait(0.2);
sanjay_ingale 0:8a0a9422787d 481
sanjay_ingale 0:8a0a9422787d 482 // Configure device for bias calculation
sanjay_ingale 0:8a0a9422787d 483 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
sanjay_ingale 0:8a0a9422787d 484 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
sanjay_ingale 0:8a0a9422787d 485 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
sanjay_ingale 0:8a0a9422787d 486 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
sanjay_ingale 0:8a0a9422787d 487 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
sanjay_ingale 0:8a0a9422787d 488 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
sanjay_ingale 0:8a0a9422787d 489 wait(0.015);
sanjay_ingale 0:8a0a9422787d 490
sanjay_ingale 0:8a0a9422787d 491 // Configure MPU9250 gyro and accelerometer for bias calculation
sanjay_ingale 0:8a0a9422787d 492 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
sanjay_ingale 0:8a0a9422787d 493 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
sanjay_ingale 0:8a0a9422787d 494 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
sanjay_ingale 0:8a0a9422787d 495 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
sanjay_ingale 0:8a0a9422787d 496
sanjay_ingale 0:8a0a9422787d 497 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
sanjay_ingale 0:8a0a9422787d 498 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
sanjay_ingale 0:8a0a9422787d 499
sanjay_ingale 0:8a0a9422787d 500 // Configure FIFO to capture accelerometer and gyro data for bias calculation
sanjay_ingale 0:8a0a9422787d 501 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
sanjay_ingale 0:8a0a9422787d 502 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
sanjay_ingale 0:8a0a9422787d 503 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
sanjay_ingale 0:8a0a9422787d 504
sanjay_ingale 0:8a0a9422787d 505 // At end of sample accumulation, turn off FIFO sensor read
sanjay_ingale 0:8a0a9422787d 506 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
sanjay_ingale 0:8a0a9422787d 507 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
sanjay_ingale 0:8a0a9422787d 508 fifo_count = ((uint16_t)data[0] << 8) | data[1];
sanjay_ingale 0:8a0a9422787d 509 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
sanjay_ingale 0:8a0a9422787d 510
sanjay_ingale 0:8a0a9422787d 511 for (ii = 0; ii < packet_count; ii++) {
sanjay_ingale 0:8a0a9422787d 512 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
sanjay_ingale 0:8a0a9422787d 513 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
sanjay_ingale 0:8a0a9422787d 514 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
sanjay_ingale 0:8a0a9422787d 515 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
sanjay_ingale 0:8a0a9422787d 516 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
sanjay_ingale 0:8a0a9422787d 517 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
sanjay_ingale 0:8a0a9422787d 518 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
sanjay_ingale 0:8a0a9422787d 519 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
sanjay_ingale 0:8a0a9422787d 520
sanjay_ingale 0:8a0a9422787d 521 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
sanjay_ingale 0:8a0a9422787d 522 accel_bias[1] += (int32_t) accel_temp[1];
sanjay_ingale 0:8a0a9422787d 523 accel_bias[2] += (int32_t) accel_temp[2];
sanjay_ingale 0:8a0a9422787d 524 gyro_bias[0] += (int32_t) gyro_temp[0];
sanjay_ingale 0:8a0a9422787d 525 gyro_bias[1] += (int32_t) gyro_temp[1];
sanjay_ingale 0:8a0a9422787d 526 gyro_bias[2] += (int32_t) gyro_temp[2];
sanjay_ingale 0:8a0a9422787d 527
sanjay_ingale 0:8a0a9422787d 528 }
sanjay_ingale 0:8a0a9422787d 529 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
sanjay_ingale 0:8a0a9422787d 530 accel_bias[1] /= (int32_t) packet_count;
sanjay_ingale 0:8a0a9422787d 531 accel_bias[2] /= (int32_t) packet_count;
sanjay_ingale 0:8a0a9422787d 532 gyro_bias[0] /= (int32_t) packet_count;
sanjay_ingale 0:8a0a9422787d 533 gyro_bias[1] /= (int32_t) packet_count;
sanjay_ingale 0:8a0a9422787d 534 gyro_bias[2] /= (int32_t) packet_count;
sanjay_ingale 0:8a0a9422787d 535
sanjay_ingale 0:8a0a9422787d 536 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation
sanjay_ingale 0:8a0a9422787d 537 else {accel_bias[2] += (int32_t) accelsensitivity;}
sanjay_ingale 0:8a0a9422787d 538
sanjay_ingale 0:8a0a9422787d 539 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
sanjay_ingale 0:8a0a9422787d 540 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
sanjay_ingale 0:8a0a9422787d 541 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
sanjay_ingale 0:8a0a9422787d 542 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
sanjay_ingale 0:8a0a9422787d 543 data[3] = (-gyro_bias[1]/4) & 0xFF;
sanjay_ingale 0:8a0a9422787d 544 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
sanjay_ingale 0:8a0a9422787d 545 data[5] = (-gyro_bias[2]/4) & 0xFF;
sanjay_ingale 0:8a0a9422787d 546
sanjay_ingale 0:8a0a9422787d 547 /// Push gyro biases to hardware registers
sanjay_ingale 0:8a0a9422787d 548 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
sanjay_ingale 0:8a0a9422787d 549 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
sanjay_ingale 0:8a0a9422787d 550 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
sanjay_ingale 0:8a0a9422787d 551 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
sanjay_ingale 0:8a0a9422787d 552 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
sanjay_ingale 0:8a0a9422787d 553 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
sanjay_ingale 0:8a0a9422787d 554 */
sanjay_ingale 0:8a0a9422787d 555 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
sanjay_ingale 0:8a0a9422787d 556 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
sanjay_ingale 0:8a0a9422787d 557 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
sanjay_ingale 0:8a0a9422787d 558
sanjay_ingale 0:8a0a9422787d 559 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
sanjay_ingale 0:8a0a9422787d 560 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
sanjay_ingale 0:8a0a9422787d 561 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
sanjay_ingale 0:8a0a9422787d 562 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
sanjay_ingale 0:8a0a9422787d 563 // the accelerometer biases calculated above must be divided by 8.
sanjay_ingale 0:8a0a9422787d 564
sanjay_ingale 0:8a0a9422787d 565 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
sanjay_ingale 0:8a0a9422787d 566 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
sanjay_ingale 0:8a0a9422787d 567 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
sanjay_ingale 0:8a0a9422787d 568 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
sanjay_ingale 0:8a0a9422787d 569 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
sanjay_ingale 0:8a0a9422787d 570 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
sanjay_ingale 0:8a0a9422787d 571 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
sanjay_ingale 0:8a0a9422787d 572
sanjay_ingale 0:8a0a9422787d 573 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
sanjay_ingale 0:8a0a9422787d 574 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
sanjay_ingale 0:8a0a9422787d 575
sanjay_ingale 0:8a0a9422787d 576 for(ii = 0; ii < 3; ii++) {
sanjay_ingale 0:8a0a9422787d 577 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
sanjay_ingale 0:8a0a9422787d 578 }
sanjay_ingale 0:8a0a9422787d 579
sanjay_ingale 0:8a0a9422787d 580 // Construct total accelerometer bias, including calculated average accelerometer bias from above
sanjay_ingale 0:8a0a9422787d 581 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
sanjay_ingale 0:8a0a9422787d 582 accel_bias_reg[1] -= (accel_bias[1]/8);
sanjay_ingale 0:8a0a9422787d 583 accel_bias_reg[2] -= (accel_bias[2]/8);
sanjay_ingale 0:8a0a9422787d 584
sanjay_ingale 0:8a0a9422787d 585 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
sanjay_ingale 0:8a0a9422787d 586 data[1] = (accel_bias_reg[0]) & 0xFF;
sanjay_ingale 0:8a0a9422787d 587 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
sanjay_ingale 0:8a0a9422787d 588 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
sanjay_ingale 0:8a0a9422787d 589 data[3] = (accel_bias_reg[1]) & 0xFF;
sanjay_ingale 0:8a0a9422787d 590 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
sanjay_ingale 0:8a0a9422787d 591 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
sanjay_ingale 0:8a0a9422787d 592 data[5] = (accel_bias_reg[2]) & 0xFF;
sanjay_ingale 0:8a0a9422787d 593 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
sanjay_ingale 0:8a0a9422787d 594
sanjay_ingale 0:8a0a9422787d 595 // Apparently this is not working for the acceleration biases in the MPU-9250
sanjay_ingale 0:8a0a9422787d 596 // Are we handling the temperature correction bit properly?
sanjay_ingale 0:8a0a9422787d 597 // Push accelerometer biases to hardware registers
sanjay_ingale 0:8a0a9422787d 598 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
sanjay_ingale 0:8a0a9422787d 599 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
sanjay_ingale 0:8a0a9422787d 600 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
sanjay_ingale 0:8a0a9422787d 601 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
sanjay_ingale 0:8a0a9422787d 602 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
sanjay_ingale 0:8a0a9422787d 603 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
sanjay_ingale 0:8a0a9422787d 604 */
sanjay_ingale 0:8a0a9422787d 605 // Output scaled accelerometer biases for manual subtraction in the main program
sanjay_ingale 0:8a0a9422787d 606 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
sanjay_ingale 0:8a0a9422787d 607 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
sanjay_ingale 0:8a0a9422787d 608 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
sanjay_ingale 0:8a0a9422787d 609 }
sanjay_ingale 0:8a0a9422787d 610
sanjay_ingale 0:8a0a9422787d 611 void magcalMPU9250(float * dest1, float * dest2)
sanjay_ingale 0:8a0a9422787d 612 {
sanjay_ingale 0:8a0a9422787d 613 uint16_t ii = 0, sample_count = 0;
sanjay_ingale 0:8a0a9422787d 614 int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0};
sanjay_ingale 0:8a0a9422787d 615 int16_t mag_max[3] = {-32767, -32767, -32767}, mag_min[3] = {32767, 32767, 32767}, mag_temp[3] = {0, 0, 0};
sanjay_ingale 0:8a0a9422787d 616
sanjay_ingale 0:8a0a9422787d 617 // shoot for ~fifteen seconds of mag data
sanjay_ingale 0:8a0a9422787d 618 if(Mmode == 0x02) sample_count = 128; // at 8 Hz ODR, new mag data is available every 125 ms
sanjay_ingale 0:8a0a9422787d 619 if(Mmode == 0x06) sample_count = 1500; // at 100 Hz ODR, new mag data is available every 10 ms
sanjay_ingale 0:8a0a9422787d 620
sanjay_ingale 0:8a0a9422787d 621 for(ii = 0; ii < sample_count; ii++) {
sanjay_ingale 0:8a0a9422787d 622 readMagData(mag_temp); // Read the mag data
sanjay_ingale 0:8a0a9422787d 623
sanjay_ingale 0:8a0a9422787d 624 for (int jj = 0; jj < 3; jj++) {
sanjay_ingale 0:8a0a9422787d 625 if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj];
sanjay_ingale 0:8a0a9422787d 626 if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj];
sanjay_ingale 0:8a0a9422787d 627 }
sanjay_ingale 0:8a0a9422787d 628
sanjay_ingale 0:8a0a9422787d 629 if(Mmode == 0x02) wait(0.135); // at 8 Hz ODR, new mag data is available every 125 ms
sanjay_ingale 0:8a0a9422787d 630 if(Mmode == 0x06) wait(0.012); // at 100 Hz ODR, new mag data is available every 10 ms
sanjay_ingale 0:8a0a9422787d 631 }
sanjay_ingale 0:8a0a9422787d 632
sanjay_ingale 0:8a0a9422787d 633 // Get hard iron correction
sanjay_ingale 0:8a0a9422787d 634 mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts
sanjay_ingale 0:8a0a9422787d 635 mag_bias[1] = (mag_max[1] + mag_min[1])/2; // get average y mag bias in counts
sanjay_ingale 0:8a0a9422787d 636 mag_bias[2] = (mag_max[2] + mag_min[2])/2; // get average z mag bias in counts
sanjay_ingale 0:8a0a9422787d 637
sanjay_ingale 0:8a0a9422787d 638 dest1[0] = (float) mag_bias[0]*mRes*magCalibration[0]; // save mag biases in G for main program
sanjay_ingale 0:8a0a9422787d 639 dest1[1] = (float) mag_bias[1]*mRes*magCalibration[1];
sanjay_ingale 0:8a0a9422787d 640 dest1[2] = (float) mag_bias[2]*mRes*magCalibration[2];
sanjay_ingale 0:8a0a9422787d 641
sanjay_ingale 0:8a0a9422787d 642 // Get soft iron correction estimate
sanjay_ingale 0:8a0a9422787d 643 mag_scale[0] = (mag_max[0] - mag_min[0])/2; // get average x axis max chord length in counts
sanjay_ingale 0:8a0a9422787d 644 mag_scale[1] = (mag_max[1] - mag_min[1])/2; // get average y axis max chord length in counts
sanjay_ingale 0:8a0a9422787d 645 mag_scale[2] = (mag_max[2] - mag_min[2])/2; // get average z axis max chord length in counts
sanjay_ingale 0:8a0a9422787d 646
sanjay_ingale 0:8a0a9422787d 647 float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2];
sanjay_ingale 0:8a0a9422787d 648 avg_rad /= 3.0;
sanjay_ingale 0:8a0a9422787d 649
sanjay_ingale 0:8a0a9422787d 650 dest2[0] = avg_rad/((float)mag_scale[0]);
sanjay_ingale 0:8a0a9422787d 651 dest2[1] = avg_rad/((float)mag_scale[1]);
sanjay_ingale 0:8a0a9422787d 652 dest2[2] = avg_rad/((float)mag_scale[2]);
sanjay_ingale 0:8a0a9422787d 653 }
sanjay_ingale 0:8a0a9422787d 654
sanjay_ingale 0:8a0a9422787d 655
sanjay_ingale 0:8a0a9422787d 656 // Accelerometer and gyroscope self test; check calibration wrt factory settings
sanjay_ingale 0:8a0a9422787d 657 void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
sanjay_ingale 0:8a0a9422787d 658 {
sanjay_ingale 0:8a0a9422787d 659 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
sanjay_ingale 0:8a0a9422787d 660 uint8_t selfTest[6];
sanjay_ingale 0:8a0a9422787d 661 int32_t gAvg[3] = {0, 0, 0}, aAvg[3] = {0, 0, 0}, aSTAvg[3] = {0, 0, 0}, gSTAvg[3] = {0, 0, 0};
sanjay_ingale 0:8a0a9422787d 662 float factoryTrim[6];
sanjay_ingale 0:8a0a9422787d 663 uint8_t FS = 0;
sanjay_ingale 0:8a0a9422787d 664
sanjay_ingale 0:8a0a9422787d 665 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
sanjay_ingale 0:8a0a9422787d 666 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
sanjay_ingale 0:8a0a9422787d 667 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
sanjay_ingale 0:8a0a9422787d 668 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
sanjay_ingale 0:8a0a9422787d 669 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
sanjay_ingale 0:8a0a9422787d 670
sanjay_ingale 0:8a0a9422787d 671 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
sanjay_ingale 0:8a0a9422787d 672
sanjay_ingale 0:8a0a9422787d 673 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
sanjay_ingale 0:8a0a9422787d 674 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 675 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 676 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 677
sanjay_ingale 0:8a0a9422787d 678 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
sanjay_ingale 0:8a0a9422787d 679 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 680 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 681 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 682 }
sanjay_ingale 0:8a0a9422787d 683
sanjay_ingale 0:8a0a9422787d 684 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
sanjay_ingale 0:8a0a9422787d 685 aAvg[ii] /= 200;
sanjay_ingale 0:8a0a9422787d 686 gAvg[ii] /= 200;
sanjay_ingale 0:8a0a9422787d 687 }
sanjay_ingale 0:8a0a9422787d 688
sanjay_ingale 0:8a0a9422787d 689 // Configure the accelerometer for self-test
sanjay_ingale 0:8a0a9422787d 690 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
sanjay_ingale 0:8a0a9422787d 691 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
sanjay_ingale 0:8a0a9422787d 692 wait(0.025); // Delay a while to let the device stabilize
sanjay_ingale 0:8a0a9422787d 693
sanjay_ingale 0:8a0a9422787d 694 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
sanjay_ingale 0:8a0a9422787d 695
sanjay_ingale 0:8a0a9422787d 696 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
sanjay_ingale 0:8a0a9422787d 697 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 698 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 699 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 700
sanjay_ingale 0:8a0a9422787d 701 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
sanjay_ingale 0:8a0a9422787d 702 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
sanjay_ingale 0:8a0a9422787d 703 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
sanjay_ingale 0:8a0a9422787d 704 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
sanjay_ingale 0:8a0a9422787d 705 }
sanjay_ingale 0:8a0a9422787d 706
sanjay_ingale 0:8a0a9422787d 707 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
sanjay_ingale 0:8a0a9422787d 708 aSTAvg[ii] /= 200;
sanjay_ingale 0:8a0a9422787d 709 gSTAvg[ii] /= 200;
sanjay_ingale 0:8a0a9422787d 710 }
sanjay_ingale 0:8a0a9422787d 711
sanjay_ingale 0:8a0a9422787d 712 // Configure the gyro and accelerometer for normal operation
sanjay_ingale 0:8a0a9422787d 713 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
sanjay_ingale 0:8a0a9422787d 714 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
sanjay_ingale 0:8a0a9422787d 715 wait(0.025); // Delay a while to let the device stabilize
sanjay_ingale 0:8a0a9422787d 716
sanjay_ingale 0:8a0a9422787d 717 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
sanjay_ingale 0:8a0a9422787d 718 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
sanjay_ingale 0:8a0a9422787d 719 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
sanjay_ingale 0:8a0a9422787d 720 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
sanjay_ingale 0:8a0a9422787d 721 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
sanjay_ingale 0:8a0a9422787d 722 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
sanjay_ingale 0:8a0a9422787d 723 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
sanjay_ingale 0:8a0a9422787d 724
sanjay_ingale 0:8a0a9422787d 725 // Retrieve factory self-test value from self-test code reads
sanjay_ingale 0:8a0a9422787d 726 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
sanjay_ingale 0:8a0a9422787d 727 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
sanjay_ingale 0:8a0a9422787d 728 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
sanjay_ingale 0:8a0a9422787d 729 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
sanjay_ingale 0:8a0a9422787d 730 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
sanjay_ingale 0:8a0a9422787d 731 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
sanjay_ingale 0:8a0a9422787d 732
sanjay_ingale 0:8a0a9422787d 733 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
sanjay_ingale 0:8a0a9422787d 734 // To get percent, must multiply by 100
sanjay_ingale 0:8a0a9422787d 735 for (int i = 0; i < 3; i++) {
sanjay_ingale 0:8a0a9422787d 736 destination[i] = 100.0f*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i] - 100.0f; // Report percent differences
sanjay_ingale 0:8a0a9422787d 737 destination[i+3] = 100.0f*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3] - 100.0f; // Report percent differences
sanjay_ingale 0:8a0a9422787d 738 }
sanjay_ingale 0:8a0a9422787d 739
sanjay_ingale 0:8a0a9422787d 740 }
sanjay_ingale 0:8a0a9422787d 741
sanjay_ingale 0:8a0a9422787d 742
sanjay_ingale 0:8a0a9422787d 743
sanjay_ingale 0:8a0a9422787d 744 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
sanjay_ingale 0:8a0a9422787d 745 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
sanjay_ingale 0:8a0a9422787d 746 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
sanjay_ingale 0:8a0a9422787d 747 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
sanjay_ingale 0:8a0a9422787d 748 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
sanjay_ingale 0:8a0a9422787d 749 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
sanjay_ingale 0:8a0a9422787d 750 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
sanjay_ingale 0:8a0a9422787d 751 {
sanjay_ingale 0:8a0a9422787d 752 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
sanjay_ingale 0:8a0a9422787d 753 float norm;
sanjay_ingale 0:8a0a9422787d 754 float hx, hy, _2bx, _2bz;
sanjay_ingale 0:8a0a9422787d 755 float s1, s2, s3, s4;
sanjay_ingale 0:8a0a9422787d 756 float qDot1, qDot2, qDot3, qDot4;
sanjay_ingale 0:8a0a9422787d 757
sanjay_ingale 0:8a0a9422787d 758 // Auxiliary variables to avoid repeated arithmetic
sanjay_ingale 0:8a0a9422787d 759 float _2q1mx;
sanjay_ingale 0:8a0a9422787d 760 float _2q1my;
sanjay_ingale 0:8a0a9422787d 761 float _2q1mz;
sanjay_ingale 0:8a0a9422787d 762 float _2q2mx;
sanjay_ingale 0:8a0a9422787d 763 float _4bx;
sanjay_ingale 0:8a0a9422787d 764 float _4bz;
sanjay_ingale 0:8a0a9422787d 765 float _2q1 = 2.0f * q1;
sanjay_ingale 0:8a0a9422787d 766 float _2q2 = 2.0f * q2;
sanjay_ingale 0:8a0a9422787d 767 float _2q3 = 2.0f * q3;
sanjay_ingale 0:8a0a9422787d 768 float _2q4 = 2.0f * q4;
sanjay_ingale 0:8a0a9422787d 769 float _2q1q3 = 2.0f * q1 * q3;
sanjay_ingale 0:8a0a9422787d 770 float _2q3q4 = 2.0f * q3 * q4;
sanjay_ingale 0:8a0a9422787d 771 float q1q1 = q1 * q1;
sanjay_ingale 0:8a0a9422787d 772 float q1q2 = q1 * q2;
sanjay_ingale 0:8a0a9422787d 773 float q1q3 = q1 * q3;
sanjay_ingale 0:8a0a9422787d 774 float q1q4 = q1 * q4;
sanjay_ingale 0:8a0a9422787d 775 float q2q2 = q2 * q2;
sanjay_ingale 0:8a0a9422787d 776 float q2q3 = q2 * q3;
sanjay_ingale 0:8a0a9422787d 777 float q2q4 = q2 * q4;
sanjay_ingale 0:8a0a9422787d 778 float q3q3 = q3 * q3;
sanjay_ingale 0:8a0a9422787d 779 float q3q4 = q3 * q4;
sanjay_ingale 0:8a0a9422787d 780 float q4q4 = q4 * q4;
sanjay_ingale 0:8a0a9422787d 781
sanjay_ingale 0:8a0a9422787d 782 // Normalise accelerometer measurement
sanjay_ingale 0:8a0a9422787d 783 norm = sqrtf(ax * ax + ay * ay + az * az);
sanjay_ingale 0:8a0a9422787d 784 if (norm == 0.0f) return; // handle NaN
sanjay_ingale 0:8a0a9422787d 785 norm = 1.0f/norm;
sanjay_ingale 0:8a0a9422787d 786 ax *= norm;
sanjay_ingale 0:8a0a9422787d 787 ay *= norm;
sanjay_ingale 0:8a0a9422787d 788 az *= norm;
sanjay_ingale 0:8a0a9422787d 789
sanjay_ingale 0:8a0a9422787d 790 // Normalise magnetometer measurement
sanjay_ingale 0:8a0a9422787d 791 norm = sqrtf(mx * mx + my * my + mz * mz);
sanjay_ingale 0:8a0a9422787d 792 if (norm == 0.0f) return; // handle NaN
sanjay_ingale 0:8a0a9422787d 793 norm = 1.0f/norm;
sanjay_ingale 0:8a0a9422787d 794 mx *= norm;
sanjay_ingale 0:8a0a9422787d 795 my *= norm;
sanjay_ingale 0:8a0a9422787d 796 mz *= norm;
sanjay_ingale 0:8a0a9422787d 797
sanjay_ingale 0:8a0a9422787d 798 // Reference direction of Earth's magnetic field
sanjay_ingale 0:8a0a9422787d 799 _2q1mx = 2.0f * q1 * mx;
sanjay_ingale 0:8a0a9422787d 800 _2q1my = 2.0f * q1 * my;
sanjay_ingale 0:8a0a9422787d 801 _2q1mz = 2.0f * q1 * mz;
sanjay_ingale 0:8a0a9422787d 802 _2q2mx = 2.0f * q2 * mx;
sanjay_ingale 0:8a0a9422787d 803 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
sanjay_ingale 0:8a0a9422787d 804 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
sanjay_ingale 0:8a0a9422787d 805 _2bx = sqrt(hx * hx + hy * hy);
sanjay_ingale 0:8a0a9422787d 806 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
sanjay_ingale 0:8a0a9422787d 807 _4bx = 2.0f * _2bx;
sanjay_ingale 0:8a0a9422787d 808 _4bz = 2.0f * _2bz;
sanjay_ingale 0:8a0a9422787d 809
sanjay_ingale 0:8a0a9422787d 810 // Gradient decent algorithm corrective step
sanjay_ingale 0:8a0a9422787d 811 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);
sanjay_ingale 0:8a0a9422787d 812 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);
sanjay_ingale 0:8a0a9422787d 813 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);
sanjay_ingale 0:8a0a9422787d 814 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);
sanjay_ingale 0:8a0a9422787d 815 norm = sqrtf(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
sanjay_ingale 0:8a0a9422787d 816 norm = 1.0f/norm;
sanjay_ingale 0:8a0a9422787d 817 s1 *= norm;
sanjay_ingale 0:8a0a9422787d 818 s2 *= norm;
sanjay_ingale 0:8a0a9422787d 819 s3 *= norm;
sanjay_ingale 0:8a0a9422787d 820 s4 *= norm;
sanjay_ingale 0:8a0a9422787d 821
sanjay_ingale 0:8a0a9422787d 822 // Compute rate of change of quaternion
sanjay_ingale 0:8a0a9422787d 823 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
sanjay_ingale 0:8a0a9422787d 824 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
sanjay_ingale 0:8a0a9422787d 825 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
sanjay_ingale 0:8a0a9422787d 826 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
sanjay_ingale 0:8a0a9422787d 827
sanjay_ingale 0:8a0a9422787d 828 // Integrate to yield quaternion
sanjay_ingale 0:8a0a9422787d 829 q1 += qDot1 * deltat;
sanjay_ingale 0:8a0a9422787d 830 q2 += qDot2 * deltat;
sanjay_ingale 0:8a0a9422787d 831 q3 += qDot3 * deltat;
sanjay_ingale 0:8a0a9422787d 832 q4 += qDot4 * deltat;
sanjay_ingale 0:8a0a9422787d 833 norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
sanjay_ingale 0:8a0a9422787d 834 norm = 1.0f/norm;
sanjay_ingale 0:8a0a9422787d 835 q[0] = q1 * norm;
sanjay_ingale 0:8a0a9422787d 836 q[1] = q2 * norm;
sanjay_ingale 0:8a0a9422787d 837 q[2] = q3 * norm;
sanjay_ingale 0:8a0a9422787d 838 q[3] = q4 * norm;
sanjay_ingale 0:8a0a9422787d 839
sanjay_ingale 0:8a0a9422787d 840 }
sanjay_ingale 0:8a0a9422787d 841
sanjay_ingale 0:8a0a9422787d 842
sanjay_ingale 0:8a0a9422787d 843
sanjay_ingale 0:8a0a9422787d 844 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
sanjay_ingale 0:8a0a9422787d 845 // measured ones.
sanjay_ingale 0:8a0a9422787d 846 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
sanjay_ingale 0:8a0a9422787d 847 {
sanjay_ingale 0:8a0a9422787d 848 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
sanjay_ingale 0:8a0a9422787d 849 float norm;
sanjay_ingale 0:8a0a9422787d 850 float hx, hy, bx, bz;
sanjay_ingale 0:8a0a9422787d 851 float vx, vy, vz, wx, wy, wz;
sanjay_ingale 0:8a0a9422787d 852 float ex, ey, ez;
sanjay_ingale 0:8a0a9422787d 853 float pa, pb, pc;
sanjay_ingale 0:8a0a9422787d 854
sanjay_ingale 0:8a0a9422787d 855 // Auxiliary variables to avoid repeated arithmetic
sanjay_ingale 0:8a0a9422787d 856 float q1q1 = q1 * q1;
sanjay_ingale 0:8a0a9422787d 857 float q1q2 = q1 * q2;
sanjay_ingale 0:8a0a9422787d 858 float q1q3 = q1 * q3;
sanjay_ingale 0:8a0a9422787d 859 float q1q4 = q1 * q4;
sanjay_ingale 0:8a0a9422787d 860 float q2q2 = q2 * q2;
sanjay_ingale 0:8a0a9422787d 861 float q2q3 = q2 * q3;
sanjay_ingale 0:8a0a9422787d 862 float q2q4 = q2 * q4;
sanjay_ingale 0:8a0a9422787d 863 float q3q3 = q3 * q3;
sanjay_ingale 0:8a0a9422787d 864 float q3q4 = q3 * q4;
sanjay_ingale 0:8a0a9422787d 865 float q4q4 = q4 * q4;
sanjay_ingale 0:8a0a9422787d 866
sanjay_ingale 0:8a0a9422787d 867 // Normalise accelerometer measurement
sanjay_ingale 0:8a0a9422787d 868 norm = sqrtf(ax * ax + ay * ay + az * az);
sanjay_ingale 0:8a0a9422787d 869 if (norm == 0.0f) return; // handle NaN
sanjay_ingale 0:8a0a9422787d 870 norm = 1.0f / norm; // use reciprocal for division
sanjay_ingale 0:8a0a9422787d 871 ax *= norm;
sanjay_ingale 0:8a0a9422787d 872 ay *= norm;
sanjay_ingale 0:8a0a9422787d 873 az *= norm;
sanjay_ingale 0:8a0a9422787d 874
sanjay_ingale 0:8a0a9422787d 875 // Normalise magnetometer measurement
sanjay_ingale 0:8a0a9422787d 876 norm = sqrtf(mx * mx + my * my + mz * mz);
sanjay_ingale 0:8a0a9422787d 877 if (norm == 0.0f) return; // handle NaN
sanjay_ingale 0:8a0a9422787d 878 norm = 1.0f / norm; // use reciprocal for division
sanjay_ingale 0:8a0a9422787d 879 mx *= norm;
sanjay_ingale 0:8a0a9422787d 880 my *= norm;
sanjay_ingale 0:8a0a9422787d 881 mz *= norm;
sanjay_ingale 0:8a0a9422787d 882
sanjay_ingale 0:8a0a9422787d 883 // Reference direction of Earth's magnetic field
sanjay_ingale 0:8a0a9422787d 884 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
sanjay_ingale 0:8a0a9422787d 885 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
sanjay_ingale 0:8a0a9422787d 886 bx = sqrtf((hx * hx) + (hy * hy));
sanjay_ingale 0:8a0a9422787d 887 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
sanjay_ingale 0:8a0a9422787d 888
sanjay_ingale 0:8a0a9422787d 889 // Estimated direction of gravity and magnetic field
sanjay_ingale 0:8a0a9422787d 890 vx = 2.0f * (q2q4 - q1q3);
sanjay_ingale 0:8a0a9422787d 891 vy = 2.0f * (q1q2 + q3q4);
sanjay_ingale 0:8a0a9422787d 892 vz = q1q1 - q2q2 - q3q3 + q4q4;
sanjay_ingale 0:8a0a9422787d 893 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
sanjay_ingale 0:8a0a9422787d 894 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
sanjay_ingale 0:8a0a9422787d 895 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
sanjay_ingale 0:8a0a9422787d 896
sanjay_ingale 0:8a0a9422787d 897 // Error is cross product between estimated direction and measured direction of gravity
sanjay_ingale 0:8a0a9422787d 898 ex = (ay * vz - az * vy) + (my * wz - mz * wy);
sanjay_ingale 0:8a0a9422787d 899 ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
sanjay_ingale 0:8a0a9422787d 900 ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
sanjay_ingale 0:8a0a9422787d 901 if (Ki > 0.0f)
sanjay_ingale 0:8a0a9422787d 902 {
sanjay_ingale 0:8a0a9422787d 903 eInt[0] += ex; // accumulate integral error
sanjay_ingale 0:8a0a9422787d 904 eInt[1] += ey;
sanjay_ingale 0:8a0a9422787d 905 eInt[2] += ez;
sanjay_ingale 0:8a0a9422787d 906 }
sanjay_ingale 0:8a0a9422787d 907 else
sanjay_ingale 0:8a0a9422787d 908 {
sanjay_ingale 0:8a0a9422787d 909 eInt[0] = 0.0f; // prevent integral wind up
sanjay_ingale 0:8a0a9422787d 910 eInt[1] = 0.0f;
sanjay_ingale 0:8a0a9422787d 911 eInt[2] = 0.0f;
sanjay_ingale 0:8a0a9422787d 912 }
sanjay_ingale 0:8a0a9422787d 913
sanjay_ingale 0:8a0a9422787d 914 // Apply feedback terms
sanjay_ingale 0:8a0a9422787d 915 gx = gx + Kp * ex + Ki * eInt[0];
sanjay_ingale 0:8a0a9422787d 916 gy = gy + Kp * ey + Ki * eInt[1];
sanjay_ingale 0:8a0a9422787d 917 gz = gz + Kp * ez + Ki * eInt[2];
sanjay_ingale 0:8a0a9422787d 918
sanjay_ingale 0:8a0a9422787d 919 // Integrate rate of change of quaternion
sanjay_ingale 0:8a0a9422787d 920 pa = q2;
sanjay_ingale 0:8a0a9422787d 921 pb = q3;
sanjay_ingale 0:8a0a9422787d 922 pc = q4;
sanjay_ingale 0:8a0a9422787d 923 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
sanjay_ingale 0:8a0a9422787d 924 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
sanjay_ingale 0:8a0a9422787d 925 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
sanjay_ingale 0:8a0a9422787d 926 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
sanjay_ingale 0:8a0a9422787d 927
sanjay_ingale 0:8a0a9422787d 928 // Normalise quaternion
sanjay_ingale 0:8a0a9422787d 929 norm = sqrtf(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
sanjay_ingale 0:8a0a9422787d 930 norm = 1.0f / norm;
sanjay_ingale 0:8a0a9422787d 931 q[0] = q1 * norm;
sanjay_ingale 0:8a0a9422787d 932 q[1] = q2 * norm;
sanjay_ingale 0:8a0a9422787d 933 q[2] = q3 * norm;
sanjay_ingale 0:8a0a9422787d 934 q[3] = q4 * norm;
sanjay_ingale 0:8a0a9422787d 935
sanjay_ingale 0:8a0a9422787d 936 }
sanjay_ingale 0:8a0a9422787d 937 };
sanjay_ingale 0:8a0a9422787d 938 #endif