MPU9250 test with polling or ISR

Dependencies:   mbed

Committer:
manitou
Date:
Mon Nov 19 11:58:46 2018 +0000
Revision:
1:0158e4d78423
Parent:
0:31cc139b7d1e
format

Who changed what in which revision?

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