kor bork wa cop koy ma

Dependencies:   mbed

Fork of testIMU2_copy2 by OX

Committer:
csggreen
Date:
Thu Dec 07 08:04:06 2017 +0000
Revision:
3:ee0df78b0dd3
Parent:
0:77a7d1a1c6db
copy koy ma

Who changed what in which revision?

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