LPC1768,MPU9250

Dependencies:   mbed

Committer:
ishiyamayuto
Date:
Wed Aug 21 08:26:38 2019 +0000
Revision:
0:f0c9082031c0
2019.8.nosiro.GeminiQuest.CanSat

Who changed what in which revision?

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