Veloc

Dependencies:   mbed

Committer:
kong4580
Date:
Fri Nov 02 05:58:27 2018 +0000
Revision:
0:3af3f05e8f7d
Mannual Calibate Press button before upload code

Who changed what in which revision?

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