v1

Dependencies:   mbed Servo

Committer:
eric11fr
Date:
Tue Oct 27 22:22:14 2020 +0000
Revision:
4:34a8e94c6fd5
Parent:
0:b8bade04f24f
test menu via xbee

Who changed what in which revision?

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