test

Dependencies:   mbed

Committer:
siwakon
Date:
Mon Dec 05 14:47:17 2016 +0000
Revision:
0:dd400e4fe461
asdasdasd

Who changed what in which revision?

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