OX V1

Dependencies:   mbed

Committer:
arthicha
Date:
Mon Dec 05 16:11:19 2016 +0000
Revision:
2:84a84429750a
Parent:
0:6182212860fb
hhh;

Who changed what in which revision?

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