bamlor

Dependencies:   mbed

Fork of mpu9250bam by Justin Bieber

Committer:
jaybehandsome
Date:
Sat Dec 09 09:47:31 2017 +0000
Revision:
0:d52e8eda04c3
yeah;

Who changed what in which revision?

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