Library version of MPU9250AHRS code.

Fork of MPU9250AHRS by Janek Mann

Committer:
janekm
Date:
Thu Sep 04 20:16:36 2014 +0000
Revision:
3:c05fbe0aef1f
Parent:
2:4e59a37182df
Child:
4:404c35f32ce3
Use pointer to i2c object.

Who changed what in which revision?

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