Added mag calibration and interrupt-based data ready

Dependencies:   BLE_API mbed-src nRF51822

Committer:
onehorse
Date:
Mon Jun 15 21:34:33 2015 +0000
Revision:
3:fe46f14f5aef
Parent:
2:4e59a37182df
Child:
4:8d11bfc7cac0
first attempt

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
onehorse 0:2e5e65a6fb30 3
onehorse 0:2e5e65a6fb30 4 #include "mbed.h"
onehorse 0:2e5e65a6fb30 5 #include "math.h"
onehorse 0:2e5e65a6fb30 6
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 29 #define SELF_TEST_X_GYRO 0x00
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 60 #define LP_ACCEL_ODR 0x1E
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 164 #endif
onehorse 0:2e5e65a6fb30 165
onehorse 0:2e5e65a6fb30 166 // Set initial input parameters
onehorse 0:2e5e65a6fb30 167 enum Ascale {
onehorse 0:2e5e65a6fb30 168 AFS_2G = 0,
onehorse 0:2e5e65a6fb30 169 AFS_4G,
onehorse 0:2e5e65a6fb30 170 AFS_8G,
onehorse 0:2e5e65a6fb30 171 AFS_16G
onehorse 0:2e5e65a6fb30 172 };
onehorse 0:2e5e65a6fb30 173
onehorse 0:2e5e65a6fb30 174 enum Gscale {
onehorse 0:2e5e65a6fb30 175 GFS_250DPS = 0,
onehorse 0:2e5e65a6fb30 176 GFS_500DPS,
onehorse 0:2e5e65a6fb30 177 GFS_1000DPS,
onehorse 0:2e5e65a6fb30 178 GFS_2000DPS
onehorse 0:2e5e65a6fb30 179 };
onehorse 0:2e5e65a6fb30 180
onehorse 0:2e5e65a6fb30 181 enum Mscale {
onehorse 0:2e5e65a6fb30 182 MFS_14BITS = 0, // 0.6 mG per LSB
onehorse 0:2e5e65a6fb30 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
onehorse 0:2e5e65a6fb30 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 3:fe46f14f5aef 193 //I2C i2c(I2C_SDA, I2C_SCL);
onehorse 3:fe46f14f5aef 194 I2C i2c(P0_20, P0_22);
onehorse 0:2e5e65a6fb30 195
onehorse 0:2e5e65a6fb30 196 DigitalOut myled(LED1);
onehorse 0:2e5e65a6fb30 197
onehorse 0:2e5e65a6fb30 198 // Pin definitions
onehorse 0:2e5e65a6fb30 199 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins
onehorse 0:2e5e65a6fb30 200
onehorse 0:2e5e65a6fb30 201 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
onehorse 0:2e5e65a6fb30 202 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
onehorse 0:2e5e65a6fb30 203 int16_t magCount[3]; // Stores the 16-bit signed magnetometer sensor output
onehorse 0:2e5e65a6fb30 204 float magCalibration[3] = {0, 0, 0}, magbias[3] = {0, 0, 0}; // Factory mag calibration and mag bias
onehorse 0:2e5e65a6fb30 205 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer
onehorse 0:2e5e65a6fb30 206 float ax, ay, az, gx, gy, gz, mx, my, mz; // variables to hold latest sensor data values
onehorse 0:2e5e65a6fb30 207 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius
onehorse 0:2e5e65a6fb30 208 float temperature;
onehorse 0:2e5e65a6fb30 209 float SelfTest[6];
onehorse 0:2e5e65a6fb30 210
onehorse 0:2e5e65a6fb30 211 int delt_t = 0; // used to control display output rate
onehorse 0:2e5e65a6fb30 212 int count = 0; // used to control display output rate
onehorse 0:2e5e65a6fb30 213
onehorse 0:2e5e65a6fb30 214 // parameters for 6 DoF sensor fusion calculations
onehorse 0:2e5e65a6fb30 215 float PI = 3.14159265358979323846f;
onehorse 0:2e5e65a6fb30 216 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 217 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta
onehorse 0:2e5e65a6fb30 218 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s)
onehorse 0:2e5e65a6fb30 219 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 220 #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 221 #define Ki 0.0f
onehorse 0:2e5e65a6fb30 222
onehorse 0:2e5e65a6fb30 223 float pitch, yaw, roll;
onehorse 0:2e5e65a6fb30 224 float deltat = 0.0f; // integration interval for both filter schemes
onehorse 0:2e5e65a6fb30 225 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval
onehorse 0:2e5e65a6fb30 226 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion
onehorse 0:2e5e65a6fb30 227 float eInt[3] = {0.0f, 0.0f, 0.0f}; // vector to hold integral error for Mahony method
onehorse 0:2e5e65a6fb30 228
onehorse 0:2e5e65a6fb30 229 class MPU9250 {
onehorse 0:2e5e65a6fb30 230
onehorse 0:2e5e65a6fb30 231 protected:
onehorse 0:2e5e65a6fb30 232
onehorse 0:2e5e65a6fb30 233 public:
onehorse 0:2e5e65a6fb30 234 //===================================================================================================================
onehorse 0:2e5e65a6fb30 235 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
onehorse 0:2e5e65a6fb30 236 //===================================================================================================================
onehorse 0:2e5e65a6fb30 237
onehorse 0:2e5e65a6fb30 238 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
onehorse 0:2e5e65a6fb30 239 {
onehorse 0:2e5e65a6fb30 240 char data_write[2];
onehorse 0:2e5e65a6fb30 241 data_write[0] = subAddress;
onehorse 0:2e5e65a6fb30 242 data_write[1] = data;
onehorse 0:2e5e65a6fb30 243 i2c.write(address, data_write, 2, 0);
onehorse 0:2e5e65a6fb30 244 }
onehorse 0:2e5e65a6fb30 245
onehorse 0:2e5e65a6fb30 246 char readByte(uint8_t address, uint8_t subAddress)
onehorse 0:2e5e65a6fb30 247 {
onehorse 0:2e5e65a6fb30 248 char data[1]; // `data` will store the register data
onehorse 0:2e5e65a6fb30 249 char data_write[1];
onehorse 0:2e5e65a6fb30 250 data_write[0] = subAddress;
onehorse 0:2e5e65a6fb30 251 i2c.write(address, data_write, 1, 1); // no stop
onehorse 0:2e5e65a6fb30 252 i2c.read(address, data, 1, 0);
onehorse 0:2e5e65a6fb30 253 return data[0];
onehorse 0:2e5e65a6fb30 254 }
onehorse 0:2e5e65a6fb30 255
onehorse 0:2e5e65a6fb30 256 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
onehorse 0:2e5e65a6fb30 257 {
onehorse 0:2e5e65a6fb30 258 char data[14];
onehorse 0:2e5e65a6fb30 259 char data_write[1];
onehorse 0:2e5e65a6fb30 260 data_write[0] = subAddress;
onehorse 0:2e5e65a6fb30 261 i2c.write(address, data_write, 1, 1); // no stop
onehorse 0:2e5e65a6fb30 262 i2c.read(address, data, count, 0);
onehorse 0:2e5e65a6fb30 263 for(int ii = 0; ii < count; ii++) {
onehorse 0:2e5e65a6fb30 264 dest[ii] = data[ii];
onehorse 0:2e5e65a6fb30 265 }
onehorse 0:2e5e65a6fb30 266 }
onehorse 0:2e5e65a6fb30 267
onehorse 0:2e5e65a6fb30 268
onehorse 0:2e5e65a6fb30 269 void getMres() {
onehorse 0:2e5e65a6fb30 270 switch (Mscale)
onehorse 0:2e5e65a6fb30 271 {
onehorse 0:2e5e65a6fb30 272 // Possible magnetometer scales (and their register bit settings) are:
onehorse 0:2e5e65a6fb30 273 // 14 bit resolution (0) and 16 bit resolution (1)
onehorse 0:2e5e65a6fb30 274 case MFS_14BITS:
onehorse 0:2e5e65a6fb30 275 mRes = 10.0*4219.0/8190.0; // Proper scale to return milliGauss
onehorse 0:2e5e65a6fb30 276 break;
onehorse 0:2e5e65a6fb30 277 case MFS_16BITS:
onehorse 0:2e5e65a6fb30 278 mRes = 10.0*4219.0/32760.0; // Proper scale to return milliGauss
onehorse 0:2e5e65a6fb30 279 break;
onehorse 0:2e5e65a6fb30 280 }
onehorse 0:2e5e65a6fb30 281 }
onehorse 0:2e5e65a6fb30 282
onehorse 0:2e5e65a6fb30 283
onehorse 0:2e5e65a6fb30 284 void getGres() {
onehorse 0:2e5e65a6fb30 285 switch (Gscale)
onehorse 0:2e5e65a6fb30 286 {
onehorse 0:2e5e65a6fb30 287 // Possible gyro scales (and their register bit settings) are:
onehorse 0:2e5e65a6fb30 288 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
onehorse 0:2e5e65a6fb30 289 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
onehorse 0:2e5e65a6fb30 290 case GFS_250DPS:
onehorse 0:2e5e65a6fb30 291 gRes = 250.0/32768.0;
onehorse 0:2e5e65a6fb30 292 break;
onehorse 0:2e5e65a6fb30 293 case GFS_500DPS:
onehorse 0:2e5e65a6fb30 294 gRes = 500.0/32768.0;
onehorse 0:2e5e65a6fb30 295 break;
onehorse 0:2e5e65a6fb30 296 case GFS_1000DPS:
onehorse 0:2e5e65a6fb30 297 gRes = 1000.0/32768.0;
onehorse 0:2e5e65a6fb30 298 break;
onehorse 0:2e5e65a6fb30 299 case GFS_2000DPS:
onehorse 0:2e5e65a6fb30 300 gRes = 2000.0/32768.0;
onehorse 0:2e5e65a6fb30 301 break;
onehorse 0:2e5e65a6fb30 302 }
onehorse 0:2e5e65a6fb30 303 }
onehorse 0:2e5e65a6fb30 304
onehorse 0:2e5e65a6fb30 305
onehorse 0:2e5e65a6fb30 306 void getAres() {
onehorse 0:2e5e65a6fb30 307 switch (Ascale)
onehorse 0:2e5e65a6fb30 308 {
onehorse 0:2e5e65a6fb30 309 // Possible accelerometer scales (and their register bit settings) are:
onehorse 0:2e5e65a6fb30 310 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
onehorse 0:2e5e65a6fb30 311 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
onehorse 0:2e5e65a6fb30 312 case AFS_2G:
onehorse 0:2e5e65a6fb30 313 aRes = 2.0/32768.0;
onehorse 0:2e5e65a6fb30 314 break;
onehorse 0:2e5e65a6fb30 315 case AFS_4G:
onehorse 0:2e5e65a6fb30 316 aRes = 4.0/32768.0;
onehorse 0:2e5e65a6fb30 317 break;
onehorse 0:2e5e65a6fb30 318 case AFS_8G:
onehorse 0:2e5e65a6fb30 319 aRes = 8.0/32768.0;
onehorse 0:2e5e65a6fb30 320 break;
onehorse 0:2e5e65a6fb30 321 case AFS_16G:
onehorse 0:2e5e65a6fb30 322 aRes = 16.0/32768.0;
onehorse 0:2e5e65a6fb30 323 break;
onehorse 0:2e5e65a6fb30 324 }
onehorse 0:2e5e65a6fb30 325 }
onehorse 0:2e5e65a6fb30 326
onehorse 0:2e5e65a6fb30 327
onehorse 0:2e5e65a6fb30 328 void readAccelData(int16_t * destination)
onehorse 0:2e5e65a6fb30 329 {
onehorse 0:2e5e65a6fb30 330 uint8_t rawData[6]; // x/y/z accel register data stored here
onehorse 0:2e5e65a6fb30 331 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
onehorse 0:2e5e65a6fb30 332 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:2e5e65a6fb30 333 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 0:2e5e65a6fb30 334 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 0:2e5e65a6fb30 335 }
onehorse 0:2e5e65a6fb30 336
onehorse 0:2e5e65a6fb30 337 void readGyroData(int16_t * destination)
onehorse 0:2e5e65a6fb30 338 {
onehorse 0:2e5e65a6fb30 339 uint8_t rawData[6]; // x/y/z gyro register data stored here
onehorse 0:2e5e65a6fb30 340 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
onehorse 0:2e5e65a6fb30 341 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:2e5e65a6fb30 342 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 0:2e5e65a6fb30 343 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 0:2e5e65a6fb30 344 }
onehorse 0:2e5e65a6fb30 345
onehorse 0:2e5e65a6fb30 346 void readMagData(int16_t * destination)
onehorse 0:2e5e65a6fb30 347 {
onehorse 0:2e5e65a6fb30 348 uint8_t rawData[7]; // x/y/z gyro register data, ST2 register stored here, must read ST2 at end of data acquisition
onehorse 0:2e5e65a6fb30 349 if(readByte(AK8963_ADDRESS, AK8963_ST1) & 0x01) { // wait for magnetometer data ready bit to be set
onehorse 0:2e5e65a6fb30 350 readBytes(AK8963_ADDRESS, AK8963_XOUT_L, 7, &rawData[0]); // Read the six raw data and ST2 registers sequentially into data array
onehorse 0:2e5e65a6fb30 351 uint8_t c = rawData[6]; // End data read by reading ST2 register
onehorse 0:2e5e65a6fb30 352 if(!(c & 0x08)) { // Check if magnetic sensor overflow set, if not then report data
onehorse 0:2e5e65a6fb30 353 destination[0] = (int16_t)(((int16_t)rawData[1] << 8) | rawData[0]); // Turn the MSB and LSB into a signed 16-bit value
onehorse 0:2e5e65a6fb30 354 destination[1] = (int16_t)(((int16_t)rawData[3] << 8) | rawData[2]) ; // Data stored as little Endian
onehorse 0:2e5e65a6fb30 355 destination[2] = (int16_t)(((int16_t)rawData[5] << 8) | rawData[4]) ;
onehorse 0:2e5e65a6fb30 356 }
onehorse 0:2e5e65a6fb30 357 }
onehorse 0:2e5e65a6fb30 358 }
onehorse 0:2e5e65a6fb30 359
onehorse 0:2e5e65a6fb30 360 int16_t readTempData()
onehorse 0:2e5e65a6fb30 361 {
onehorse 0:2e5e65a6fb30 362 uint8_t rawData[2]; // x/y/z gyro register data stored here
onehorse 0:2e5e65a6fb30 363 readBytes(MPU9250_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array
onehorse 0:2e5e65a6fb30 364 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value
onehorse 0:2e5e65a6fb30 365 }
onehorse 0:2e5e65a6fb30 366
onehorse 0:2e5e65a6fb30 367
onehorse 0:2e5e65a6fb30 368 void resetMPU9250() {
onehorse 0:2e5e65a6fb30 369 // reset device
onehorse 0:2e5e65a6fb30 370 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
onehorse 0:2e5e65a6fb30 371 wait(0.1);
onehorse 0:2e5e65a6fb30 372 }
onehorse 0:2e5e65a6fb30 373
onehorse 0:2e5e65a6fb30 374 void initAK8963(float * destination)
onehorse 0:2e5e65a6fb30 375 {
onehorse 0:2e5e65a6fb30 376 // First extract the factory calibration for each magnetometer axis
onehorse 0:2e5e65a6fb30 377 uint8_t rawData[3]; // x/y/z gyro calibration data stored here
onehorse 0:2e5e65a6fb30 378 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
onehorse 0:2e5e65a6fb30 379 wait(0.01);
onehorse 0:2e5e65a6fb30 380 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x0F); // Enter Fuse ROM access mode
onehorse 0:2e5e65a6fb30 381 wait(0.01);
onehorse 0:2e5e65a6fb30 382 readBytes(AK8963_ADDRESS, AK8963_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values
onehorse 0:2e5e65a6fb30 383 destination[0] = (float)(rawData[0] - 128)/256.0f + 1.0f; // Return x-axis sensitivity adjustment values, etc.
onehorse 0:2e5e65a6fb30 384 destination[1] = (float)(rawData[1] - 128)/256.0f + 1.0f;
onehorse 0:2e5e65a6fb30 385 destination[2] = (float)(rawData[2] - 128)/256.0f + 1.0f;
onehorse 0:2e5e65a6fb30 386 writeByte(AK8963_ADDRESS, AK8963_CNTL, 0x00); // Power down magnetometer
onehorse 0:2e5e65a6fb30 387 wait(0.01);
onehorse 0:2e5e65a6fb30 388 // Configure the magnetometer for continuous read and highest resolution
onehorse 0:2e5e65a6fb30 389 // set Mscale bit 4 to 1 (0) to enable 16 (14) bit resolution in CNTL register,
onehorse 0:2e5e65a6fb30 390 // and enable continuous mode data acquisition Mmode (bits [3:0]), 0010 for 8 Hz and 0110 for 100 Hz sample rates
onehorse 0:2e5e65a6fb30 391 writeByte(AK8963_ADDRESS, AK8963_CNTL, Mscale << 4 | Mmode); // Set magnetometer data resolution and sample ODR
onehorse 0:2e5e65a6fb30 392 wait(0.01);
onehorse 0:2e5e65a6fb30 393 }
onehorse 0:2e5e65a6fb30 394
onehorse 0:2e5e65a6fb30 395
onehorse 0:2e5e65a6fb30 396 void initMPU9250()
onehorse 0:2e5e65a6fb30 397 {
onehorse 0:2e5e65a6fb30 398 // Initialize MPU9250 device
onehorse 0:2e5e65a6fb30 399 // wake up device
onehorse 0:2e5e65a6fb30 400 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors
onehorse 0:2e5e65a6fb30 401 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt
onehorse 0:2e5e65a6fb30 402
onehorse 0:2e5e65a6fb30 403 // get stable time source
onehorse 0:2e5e65a6fb30 404 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 405
onehorse 0:2e5e65a6fb30 406 // Configure Gyro and Accelerometer
onehorse 0:2e5e65a6fb30 407 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively;
onehorse 0:2e5e65a6fb30 408 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
onehorse 0:2e5e65a6fb30 409 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
onehorse 0:2e5e65a6fb30 410 writeByte(MPU9250_ADDRESS, CONFIG, 0x03);
onehorse 0:2e5e65a6fb30 411
onehorse 0:2e5e65a6fb30 412 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
onehorse 0:2e5e65a6fb30 413 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
onehorse 0:2e5e65a6fb30 414
onehorse 0:2e5e65a6fb30 415 // Set gyroscope full scale range
onehorse 0:2e5e65a6fb30 416 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
onehorse 0:2e5e65a6fb30 417 uint8_t c = readByte(MPU9250_ADDRESS, GYRO_CONFIG);
onehorse 0:2e5e65a6fb30 418 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
onehorse 0:2e5e65a6fb30 419 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
onehorse 0:2e5e65a6fb30 420 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
onehorse 0:2e5e65a6fb30 421
onehorse 0:2e5e65a6fb30 422 // Set accelerometer configuration
onehorse 0:2e5e65a6fb30 423 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG);
onehorse 0:2e5e65a6fb30 424 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5]
onehorse 0:2e5e65a6fb30 425 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
onehorse 0:2e5e65a6fb30 426 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer
onehorse 0:2e5e65a6fb30 427
onehorse 0:2e5e65a6fb30 428 // Set accelerometer sample rate configuration
onehorse 0:2e5e65a6fb30 429 // It is possible to get a 4 kHz sample rate from the accelerometer by choosing 1 for
onehorse 0:2e5e65a6fb30 430 // accel_fchoice_b bit [3]; in this case the bandwidth is 1.13 kHz
onehorse 0:2e5e65a6fb30 431 c = readByte(MPU9250_ADDRESS, ACCEL_CONFIG2);
onehorse 0:2e5e65a6fb30 432 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c & ~0x0F); // Clear accel_fchoice_b (bit 3) and A_DLPFG (bits [2:0])
onehorse 0:2e5e65a6fb30 433 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, c | 0x03); // Set accelerometer rate to 1 kHz and bandwidth to 41 Hz
onehorse 0:2e5e65a6fb30 434
onehorse 0:2e5e65a6fb30 435 // The accelerometer, gyro, and thermometer are set to 1 kHz sample rates,
onehorse 0:2e5e65a6fb30 436 // but all these rates are further reduced by a factor of 5 to 200 Hz because of the SMPLRT_DIV setting
onehorse 0:2e5e65a6fb30 437
onehorse 0:2e5e65a6fb30 438 // Configure Interrupts and Bypass Enable
onehorse 0:2e5e65a6fb30 439 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips
onehorse 0:2e5e65a6fb30 440 // can join the I2C bus and all can be controlled by the Arduino as master
onehorse 0:2e5e65a6fb30 441 writeByte(MPU9250_ADDRESS, INT_PIN_CFG, 0x22);
onehorse 0:2e5e65a6fb30 442 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt
onehorse 0:2e5e65a6fb30 443 }
onehorse 0:2e5e65a6fb30 444
onehorse 0:2e5e65a6fb30 445 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
onehorse 0:2e5e65a6fb30 446 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
onehorse 0:2e5e65a6fb30 447 void calibrateMPU9250(float * dest1, float * dest2)
onehorse 0:2e5e65a6fb30 448 {
onehorse 0:2e5e65a6fb30 449 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
onehorse 0:2e5e65a6fb30 450 uint16_t ii, packet_count, fifo_count;
onehorse 0:2e5e65a6fb30 451 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
onehorse 0:2e5e65a6fb30 452
onehorse 0:2e5e65a6fb30 453 // reset device, reset all registers, clear gyro and accelerometer bias registers
onehorse 0:2e5e65a6fb30 454 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
onehorse 0:2e5e65a6fb30 455 wait(0.1);
onehorse 0:2e5e65a6fb30 456
onehorse 0:2e5e65a6fb30 457 // get stable time source
onehorse 0:2e5e65a6fb30 458 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
onehorse 0:2e5e65a6fb30 459 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x01);
onehorse 0:2e5e65a6fb30 460 writeByte(MPU9250_ADDRESS, PWR_MGMT_2, 0x00);
onehorse 0:2e5e65a6fb30 461 wait(0.2);
onehorse 0:2e5e65a6fb30 462
onehorse 0:2e5e65a6fb30 463 // Configure device for bias calculation
onehorse 0:2e5e65a6fb30 464 writeByte(MPU9250_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
onehorse 0:2e5e65a6fb30 465 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
onehorse 0:2e5e65a6fb30 466 writeByte(MPU9250_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source
onehorse 0:2e5e65a6fb30 467 writeByte(MPU9250_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
onehorse 0:2e5e65a6fb30 468 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes
onehorse 0:2e5e65a6fb30 469 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
onehorse 0:2e5e65a6fb30 470 wait(0.015);
onehorse 0:2e5e65a6fb30 471
onehorse 0:2e5e65a6fb30 472 // Configure MPU9250 gyro and accelerometer for bias calculation
onehorse 0:2e5e65a6fb30 473 writeByte(MPU9250_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
onehorse 0:2e5e65a6fb30 474 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
onehorse 0:2e5e65a6fb30 475 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity
onehorse 0:2e5e65a6fb30 476 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
onehorse 0:2e5e65a6fb30 477
onehorse 0:2e5e65a6fb30 478 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
onehorse 0:2e5e65a6fb30 479 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
onehorse 0:2e5e65a6fb30 480
onehorse 0:2e5e65a6fb30 481 // Configure FIFO to capture accelerometer and gyro data for bias calculation
onehorse 0:2e5e65a6fb30 482 writeByte(MPU9250_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
onehorse 0:2e5e65a6fb30 483 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 512 bytes in MPU-9250)
onehorse 0:2e5e65a6fb30 484 wait(0.04); // accumulate 40 samples in 80 milliseconds = 480 bytes
onehorse 0:2e5e65a6fb30 485
onehorse 0:2e5e65a6fb30 486 // At end of sample accumulation, turn off FIFO sensor read
onehorse 0:2e5e65a6fb30 487 writeByte(MPU9250_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO
onehorse 0:2e5e65a6fb30 488 readBytes(MPU9250_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
onehorse 0:2e5e65a6fb30 489 fifo_count = ((uint16_t)data[0] << 8) | data[1];
onehorse 0:2e5e65a6fb30 490 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
onehorse 0:2e5e65a6fb30 491
onehorse 0:2e5e65a6fb30 492 for (ii = 0; ii < packet_count; ii++) {
onehorse 0:2e5e65a6fb30 493 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
onehorse 0:2e5e65a6fb30 494 readBytes(MPU9250_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
onehorse 0:2e5e65a6fb30 495 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO
onehorse 0:2e5e65a6fb30 496 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ;
onehorse 0:2e5e65a6fb30 497 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ;
onehorse 0:2e5e65a6fb30 498 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ;
onehorse 0:2e5e65a6fb30 499 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ;
onehorse 0:2e5e65a6fb30 500 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
onehorse 0:2e5e65a6fb30 501
onehorse 0:2e5e65a6fb30 502 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
onehorse 0:2e5e65a6fb30 503 accel_bias[1] += (int32_t) accel_temp[1];
onehorse 0:2e5e65a6fb30 504 accel_bias[2] += (int32_t) accel_temp[2];
onehorse 0:2e5e65a6fb30 505 gyro_bias[0] += (int32_t) gyro_temp[0];
onehorse 0:2e5e65a6fb30 506 gyro_bias[1] += (int32_t) gyro_temp[1];
onehorse 0:2e5e65a6fb30 507 gyro_bias[2] += (int32_t) gyro_temp[2];
onehorse 0:2e5e65a6fb30 508
onehorse 0:2e5e65a6fb30 509 }
onehorse 0:2e5e65a6fb30 510 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
onehorse 0:2e5e65a6fb30 511 accel_bias[1] /= (int32_t) packet_count;
onehorse 0:2e5e65a6fb30 512 accel_bias[2] /= (int32_t) packet_count;
onehorse 0:2e5e65a6fb30 513 gyro_bias[0] /= (int32_t) packet_count;
onehorse 0:2e5e65a6fb30 514 gyro_bias[1] /= (int32_t) packet_count;
onehorse 0:2e5e65a6fb30 515 gyro_bias[2] /= (int32_t) packet_count;
onehorse 0:2e5e65a6fb30 516
onehorse 0:2e5e65a6fb30 517 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation
onehorse 0:2e5e65a6fb30 518 else {accel_bias[2] += (int32_t) accelsensitivity;}
onehorse 0:2e5e65a6fb30 519
onehorse 0:2e5e65a6fb30 520 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
onehorse 0:2e5e65a6fb30 521 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
onehorse 0:2e5e65a6fb30 522 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
onehorse 0:2e5e65a6fb30 523 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF;
onehorse 0:2e5e65a6fb30 524 data[3] = (-gyro_bias[1]/4) & 0xFF;
onehorse 0:2e5e65a6fb30 525 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF;
onehorse 0:2e5e65a6fb30 526 data[5] = (-gyro_bias[2]/4) & 0xFF;
onehorse 0:2e5e65a6fb30 527
onehorse 0:2e5e65a6fb30 528 /// Push gyro biases to hardware registers
onehorse 0:2e5e65a6fb30 529 /* writeByte(MPU9250_ADDRESS, XG_OFFSET_H, data[0]);
onehorse 0:2e5e65a6fb30 530 writeByte(MPU9250_ADDRESS, XG_OFFSET_L, data[1]);
onehorse 0:2e5e65a6fb30 531 writeByte(MPU9250_ADDRESS, YG_OFFSET_H, data[2]);
onehorse 0:2e5e65a6fb30 532 writeByte(MPU9250_ADDRESS, YG_OFFSET_L, data[3]);
onehorse 0:2e5e65a6fb30 533 writeByte(MPU9250_ADDRESS, ZG_OFFSET_H, data[4]);
onehorse 0:2e5e65a6fb30 534 writeByte(MPU9250_ADDRESS, ZG_OFFSET_L, data[5]);
onehorse 0:2e5e65a6fb30 535 */
onehorse 0:2e5e65a6fb30 536 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
onehorse 0:2e5e65a6fb30 537 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
onehorse 0:2e5e65a6fb30 538 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
onehorse 0:2e5e65a6fb30 539
onehorse 0:2e5e65a6fb30 540 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
onehorse 0:2e5e65a6fb30 541 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
onehorse 0:2e5e65a6fb30 542 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
onehorse 0:2e5e65a6fb30 543 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
onehorse 0:2e5e65a6fb30 544 // the accelerometer biases calculated above must be divided by 8.
onehorse 0:2e5e65a6fb30 545
onehorse 0:2e5e65a6fb30 546 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
onehorse 0:2e5e65a6fb30 547 readBytes(MPU9250_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
onehorse 0:2e5e65a6fb30 548 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:2e5e65a6fb30 549 readBytes(MPU9250_ADDRESS, YA_OFFSET_H, 2, &data[0]);
onehorse 0:2e5e65a6fb30 550 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:2e5e65a6fb30 551 readBytes(MPU9250_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
onehorse 0:2e5e65a6fb30 552 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
onehorse 0:2e5e65a6fb30 553
onehorse 0:2e5e65a6fb30 554 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
onehorse 0:2e5e65a6fb30 555 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
onehorse 0:2e5e65a6fb30 556
onehorse 0:2e5e65a6fb30 557 for(ii = 0; ii < 3; ii++) {
onehorse 0:2e5e65a6fb30 558 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
onehorse 0:2e5e65a6fb30 559 }
onehorse 0:2e5e65a6fb30 560
onehorse 0:2e5e65a6fb30 561 // Construct total accelerometer bias, including calculated average accelerometer bias from above
onehorse 0:2e5e65a6fb30 562 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
onehorse 0:2e5e65a6fb30 563 accel_bias_reg[1] -= (accel_bias[1]/8);
onehorse 0:2e5e65a6fb30 564 accel_bias_reg[2] -= (accel_bias[2]/8);
onehorse 0:2e5e65a6fb30 565
onehorse 0:2e5e65a6fb30 566 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
onehorse 0:2e5e65a6fb30 567 data[1] = (accel_bias_reg[0]) & 0xFF;
onehorse 0:2e5e65a6fb30 568 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:2e5e65a6fb30 569 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
onehorse 0:2e5e65a6fb30 570 data[3] = (accel_bias_reg[1]) & 0xFF;
onehorse 0:2e5e65a6fb30 571 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:2e5e65a6fb30 572 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
onehorse 0:2e5e65a6fb30 573 data[5] = (accel_bias_reg[2]) & 0xFF;
onehorse 0:2e5e65a6fb30 574 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
onehorse 0:2e5e65a6fb30 575
onehorse 0:2e5e65a6fb30 576 // Apparently this is not working for the acceleration biases in the MPU-9250
onehorse 0:2e5e65a6fb30 577 // Are we handling the temperature correction bit properly?
onehorse 0:2e5e65a6fb30 578 // Push accelerometer biases to hardware registers
onehorse 0:2e5e65a6fb30 579 /* writeByte(MPU9250_ADDRESS, XA_OFFSET_H, data[0]);
onehorse 0:2e5e65a6fb30 580 writeByte(MPU9250_ADDRESS, XA_OFFSET_L, data[1]);
onehorse 0:2e5e65a6fb30 581 writeByte(MPU9250_ADDRESS, YA_OFFSET_H, data[2]);
onehorse 0:2e5e65a6fb30 582 writeByte(MPU9250_ADDRESS, YA_OFFSET_L, data[3]);
onehorse 0:2e5e65a6fb30 583 writeByte(MPU9250_ADDRESS, ZA_OFFSET_H, data[4]);
onehorse 0:2e5e65a6fb30 584 writeByte(MPU9250_ADDRESS, ZA_OFFSET_L, data[5]);
onehorse 0:2e5e65a6fb30 585 */
onehorse 0:2e5e65a6fb30 586 // Output scaled accelerometer biases for manual subtraction in the main program
onehorse 0:2e5e65a6fb30 587 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity;
onehorse 0:2e5e65a6fb30 588 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
onehorse 0:2e5e65a6fb30 589 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
onehorse 0:2e5e65a6fb30 590 }
onehorse 0:2e5e65a6fb30 591
onehorse 0:2e5e65a6fb30 592
onehorse 0:2e5e65a6fb30 593 // Accelerometer and gyroscope self test; check calibration wrt factory settings
onehorse 0:2e5e65a6fb30 594 void MPU9250SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
onehorse 0:2e5e65a6fb30 595 {
onehorse 2:4e59a37182df 596 uint8_t rawData[6] = {0, 0, 0, 0, 0, 0};
onehorse 0:2e5e65a6fb30 597 uint8_t selfTest[6];
onehorse 2:4e59a37182df 598 int16_t gAvg[3], aAvg[3], aSTAvg[3], gSTAvg[3];
onehorse 0:2e5e65a6fb30 599 float factoryTrim[6];
onehorse 2:4e59a37182df 600 uint8_t FS = 0;
onehorse 0:2e5e65a6fb30 601
onehorse 2:4e59a37182df 602 writeByte(MPU9250_ADDRESS, SMPLRT_DIV, 0x00); // Set gyro sample rate to 1 kHz
onehorse 2:4e59a37182df 603 writeByte(MPU9250_ADDRESS, CONFIG, 0x02); // Set gyro sample rate to 1 kHz and DLPF to 92 Hz
onehorse 2:4e59a37182df 604 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 1<<FS); // Set full scale range for the gyro to 250 dps
onehorse 2:4e59a37182df 605 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG2, 0x02); // Set accelerometer rate to 1 kHz and bandwidth to 92 Hz
onehorse 2:4e59a37182df 606 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 1<<FS); // Set full scale range for the accelerometer to 2 g
onehorse 2:4e59a37182df 607
onehorse 2:4e59a37182df 608 for( int ii = 0; ii < 200; ii++) { // get average current values of gyro and acclerometer
onehorse 2:4e59a37182df 609
onehorse 2:4e59a37182df 610 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
onehorse 2:4e59a37182df 611 aAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 2:4e59a37182df 612 aAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 2:4e59a37182df 613 aAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 2:4e59a37182df 614
onehorse 2:4e59a37182df 615 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
onehorse 2:4e59a37182df 616 gAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 2:4e59a37182df 617 gAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 2:4e59a37182df 618 gAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 2:4e59a37182df 619 }
onehorse 2:4e59a37182df 620
onehorse 2:4e59a37182df 621 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average current readings
onehorse 2:4e59a37182df 622 aAvg[ii] /= 200;
onehorse 2:4e59a37182df 623 gAvg[ii] /= 200;
onehorse 2:4e59a37182df 624 }
onehorse 2:4e59a37182df 625
onehorse 2:4e59a37182df 626 // Configure the accelerometer for self-test
onehorse 2:4e59a37182df 627 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0xE0); // Enable self test on all three axes and set accelerometer range to +/- 2 g
onehorse 2:4e59a37182df 628 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
onehorse 3:fe46f14f5aef 629 wait(0.025); // Delay a while to let the device stabilize
onehorse 2:4e59a37182df 630
onehorse 2:4e59a37182df 631 for( int ii = 0; ii < 200; ii++) { // get average self-test values of gyro and acclerometer
onehorse 2:4e59a37182df 632
onehorse 2:4e59a37182df 633 readBytes(MPU9250_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array
onehorse 2:4e59a37182df 634 aSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 2:4e59a37182df 635 aSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 2:4e59a37182df 636 aSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 2:4e59a37182df 637
onehorse 2:4e59a37182df 638 readBytes(MPU9250_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array
onehorse 2:4e59a37182df 639 gSTAvg[0] += (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value
onehorse 2:4e59a37182df 640 gSTAvg[1] += (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;
onehorse 2:4e59a37182df 641 gSTAvg[2] += (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ;
onehorse 2:4e59a37182df 642 }
onehorse 2:4e59a37182df 643
onehorse 2:4e59a37182df 644 for (int ii =0; ii < 3; ii++) { // Get average of 200 values and store as average self-test readings
onehorse 2:4e59a37182df 645 aSTAvg[ii] /= 200;
onehorse 2:4e59a37182df 646 gSTAvg[ii] /= 200;
onehorse 2:4e59a37182df 647 }
onehorse 2:4e59a37182df 648
onehorse 2:4e59a37182df 649 // Configure the gyro and accelerometer for normal operation
onehorse 2:4e59a37182df 650 writeByte(MPU9250_ADDRESS, ACCEL_CONFIG, 0x00);
onehorse 2:4e59a37182df 651 writeByte(MPU9250_ADDRESS, GYRO_CONFIG, 0x00);
onehorse 3:fe46f14f5aef 652 wait(0.025); // Delay a while to let the device stabilize
onehorse 0:2e5e65a6fb30 653
onehorse 2:4e59a37182df 654 // Retrieve accelerometer and gyro factory Self-Test Code from USR_Reg
onehorse 2:4e59a37182df 655 selfTest[0] = readByte(MPU9250_ADDRESS, SELF_TEST_X_ACCEL); // X-axis accel self-test results
onehorse 2:4e59a37182df 656 selfTest[1] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_ACCEL); // Y-axis accel self-test results
onehorse 2:4e59a37182df 657 selfTest[2] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_ACCEL); // Z-axis accel self-test results
onehorse 2:4e59a37182df 658 selfTest[3] = readByte(MPU9250_ADDRESS, SELF_TEST_X_GYRO); // X-axis gyro self-test results
onehorse 2:4e59a37182df 659 selfTest[4] = readByte(MPU9250_ADDRESS, SELF_TEST_Y_GYRO); // Y-axis gyro self-test results
onehorse 2:4e59a37182df 660 selfTest[5] = readByte(MPU9250_ADDRESS, SELF_TEST_Z_GYRO); // Z-axis gyro self-test results
onehorse 0:2e5e65a6fb30 661
onehorse 2:4e59a37182df 662 // Retrieve factory self-test value from self-test code reads
onehorse 2:4e59a37182df 663 factoryTrim[0] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[0] - 1.0) )); // FT[Xa] factory trim calculation
onehorse 2:4e59a37182df 664 factoryTrim[1] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[1] - 1.0) )); // FT[Ya] factory trim calculation
onehorse 2:4e59a37182df 665 factoryTrim[2] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[2] - 1.0) )); // FT[Za] factory trim calculation
onehorse 2:4e59a37182df 666 factoryTrim[3] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[3] - 1.0) )); // FT[Xg] factory trim calculation
onehorse 2:4e59a37182df 667 factoryTrim[4] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[4] - 1.0) )); // FT[Yg] factory trim calculation
onehorse 2:4e59a37182df 668 factoryTrim[5] = (float)(2620/1<<FS)*(pow( 1.01 , ((float)selfTest[5] - 1.0) )); // FT[Zg] factory trim calculation
onehorse 2:4e59a37182df 669
onehorse 0:2e5e65a6fb30 670 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
onehorse 2:4e59a37182df 671 // To get percent, must multiply by 100
onehorse 2:4e59a37182df 672 for (int i = 0; i < 3; i++) {
onehorse 2:4e59a37182df 673 destination[i] = 100.0*((float)(aSTAvg[i] - aAvg[i]))/factoryTrim[i]; // Report percent differences
onehorse 2:4e59a37182df 674 destination[i+3] = 100.0*((float)(gSTAvg[i] - gAvg[i]))/factoryTrim[i+3]; // Report percent differences
onehorse 0:2e5e65a6fb30 675 }
onehorse 0:2e5e65a6fb30 676
onehorse 0:2e5e65a6fb30 677 }
onehorse 0:2e5e65a6fb30 678
onehorse 0:2e5e65a6fb30 679
onehorse 0:2e5e65a6fb30 680
onehorse 0:2e5e65a6fb30 681 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
onehorse 0:2e5e65a6fb30 682 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
onehorse 0:2e5e65a6fb30 683 // which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute
onehorse 0:2e5e65a6fb30 684 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
onehorse 0:2e5e65a6fb30 685 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
onehorse 0:2e5e65a6fb30 686 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
onehorse 0:2e5e65a6fb30 687 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
onehorse 0:2e5e65a6fb30 688 {
onehorse 0:2e5e65a6fb30 689 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
onehorse 0:2e5e65a6fb30 690 float norm;
onehorse 0:2e5e65a6fb30 691 float hx, hy, _2bx, _2bz;
onehorse 0:2e5e65a6fb30 692 float s1, s2, s3, s4;
onehorse 0:2e5e65a6fb30 693 float qDot1, qDot2, qDot3, qDot4;
onehorse 0:2e5e65a6fb30 694
onehorse 0:2e5e65a6fb30 695 // Auxiliary variables to avoid repeated arithmetic
onehorse 0:2e5e65a6fb30 696 float _2q1mx;
onehorse 0:2e5e65a6fb30 697 float _2q1my;
onehorse 0:2e5e65a6fb30 698 float _2q1mz;
onehorse 0:2e5e65a6fb30 699 float _2q2mx;
onehorse 0:2e5e65a6fb30 700 float _4bx;
onehorse 0:2e5e65a6fb30 701 float _4bz;
onehorse 0:2e5e65a6fb30 702 float _2q1 = 2.0f * q1;
onehorse 0:2e5e65a6fb30 703 float _2q2 = 2.0f * q2;
onehorse 0:2e5e65a6fb30 704 float _2q3 = 2.0f * q3;
onehorse 0:2e5e65a6fb30 705 float _2q4 = 2.0f * q4;
onehorse 0:2e5e65a6fb30 706 float _2q1q3 = 2.0f * q1 * q3;
onehorse 0:2e5e65a6fb30 707 float _2q3q4 = 2.0f * q3 * q4;
onehorse 0:2e5e65a6fb30 708 float q1q1 = q1 * q1;
onehorse 0:2e5e65a6fb30 709 float q1q2 = q1 * q2;
onehorse 0:2e5e65a6fb30 710 float q1q3 = q1 * q3;
onehorse 0:2e5e65a6fb30 711 float q1q4 = q1 * q4;
onehorse 0:2e5e65a6fb30 712 float q2q2 = q2 * q2;
onehorse 0:2e5e65a6fb30 713 float q2q3 = q2 * q3;
onehorse 0:2e5e65a6fb30 714 float q2q4 = q2 * q4;
onehorse 0:2e5e65a6fb30 715 float q3q3 = q3 * q3;
onehorse 0:2e5e65a6fb30 716 float q3q4 = q3 * q4;
onehorse 0:2e5e65a6fb30 717 float q4q4 = q4 * q4;
onehorse 0:2e5e65a6fb30 718
onehorse 0:2e5e65a6fb30 719 // Normalise accelerometer measurement
onehorse 0:2e5e65a6fb30 720 norm = sqrt(ax * ax + ay * ay + az * az);
onehorse 0:2e5e65a6fb30 721 if (norm == 0.0f) return; // handle NaN
onehorse 0:2e5e65a6fb30 722 norm = 1.0f/norm;
onehorse 0:2e5e65a6fb30 723 ax *= norm;
onehorse 0:2e5e65a6fb30 724 ay *= norm;
onehorse 0:2e5e65a6fb30 725 az *= norm;
onehorse 0:2e5e65a6fb30 726
onehorse 0:2e5e65a6fb30 727 // Normalise magnetometer measurement
onehorse 0:2e5e65a6fb30 728 norm = sqrt(mx * mx + my * my + mz * mz);
onehorse 0:2e5e65a6fb30 729 if (norm == 0.0f) return; // handle NaN
onehorse 0:2e5e65a6fb30 730 norm = 1.0f/norm;
onehorse 0:2e5e65a6fb30 731 mx *= norm;
onehorse 0:2e5e65a6fb30 732 my *= norm;
onehorse 0:2e5e65a6fb30 733 mz *= norm;
onehorse 0:2e5e65a6fb30 734
onehorse 0:2e5e65a6fb30 735 // Reference direction of Earth's magnetic field
onehorse 0:2e5e65a6fb30 736 _2q1mx = 2.0f * q1 * mx;
onehorse 0:2e5e65a6fb30 737 _2q1my = 2.0f * q1 * my;
onehorse 0:2e5e65a6fb30 738 _2q1mz = 2.0f * q1 * mz;
onehorse 0:2e5e65a6fb30 739 _2q2mx = 2.0f * q2 * mx;
onehorse 0:2e5e65a6fb30 740 hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4;
onehorse 0:2e5e65a6fb30 741 hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4;
onehorse 0:2e5e65a6fb30 742 _2bx = sqrt(hx * hx + hy * hy);
onehorse 0:2e5e65a6fb30 743 _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4;
onehorse 0:2e5e65a6fb30 744 _4bx = 2.0f * _2bx;
onehorse 0:2e5e65a6fb30 745 _4bz = 2.0f * _2bz;
onehorse 0:2e5e65a6fb30 746
onehorse 0:2e5e65a6fb30 747 // Gradient decent algorithm corrective step
onehorse 0:2e5e65a6fb30 748 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);
onehorse 0:2e5e65a6fb30 749 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);
onehorse 0:2e5e65a6fb30 750 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);
onehorse 0:2e5e65a6fb30 751 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);
onehorse 0:2e5e65a6fb30 752 norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude
onehorse 0:2e5e65a6fb30 753 norm = 1.0f/norm;
onehorse 0:2e5e65a6fb30 754 s1 *= norm;
onehorse 0:2e5e65a6fb30 755 s2 *= norm;
onehorse 0:2e5e65a6fb30 756 s3 *= norm;
onehorse 0:2e5e65a6fb30 757 s4 *= norm;
onehorse 0:2e5e65a6fb30 758
onehorse 0:2e5e65a6fb30 759 // Compute rate of change of quaternion
onehorse 0:2e5e65a6fb30 760 qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1;
onehorse 0:2e5e65a6fb30 761 qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2;
onehorse 0:2e5e65a6fb30 762 qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3;
onehorse 0:2e5e65a6fb30 763 qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4;
onehorse 0:2e5e65a6fb30 764
onehorse 0:2e5e65a6fb30 765 // Integrate to yield quaternion
onehorse 0:2e5e65a6fb30 766 q1 += qDot1 * deltat;
onehorse 0:2e5e65a6fb30 767 q2 += qDot2 * deltat;
onehorse 0:2e5e65a6fb30 768 q3 += qDot3 * deltat;
onehorse 0:2e5e65a6fb30 769 q4 += qDot4 * deltat;
onehorse 0:2e5e65a6fb30 770 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
onehorse 0:2e5e65a6fb30 771 norm = 1.0f/norm;
onehorse 0:2e5e65a6fb30 772 q[0] = q1 * norm;
onehorse 0:2e5e65a6fb30 773 q[1] = q2 * norm;
onehorse 0:2e5e65a6fb30 774 q[2] = q3 * norm;
onehorse 0:2e5e65a6fb30 775 q[3] = q4 * norm;
onehorse 0:2e5e65a6fb30 776
onehorse 0:2e5e65a6fb30 777 }
onehorse 0:2e5e65a6fb30 778
onehorse 0:2e5e65a6fb30 779
onehorse 0:2e5e65a6fb30 780
onehorse 0:2e5e65a6fb30 781 // Similar to Madgwick scheme but uses proportional and integral filtering on the error between estimated reference vectors and
onehorse 0:2e5e65a6fb30 782 // measured ones.
onehorse 0:2e5e65a6fb30 783 void MahonyQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz)
onehorse 0:2e5e65a6fb30 784 {
onehorse 0:2e5e65a6fb30 785 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability
onehorse 0:2e5e65a6fb30 786 float norm;
onehorse 0:2e5e65a6fb30 787 float hx, hy, bx, bz;
onehorse 0:2e5e65a6fb30 788 float vx, vy, vz, wx, wy, wz;
onehorse 0:2e5e65a6fb30 789 float ex, ey, ez;
onehorse 0:2e5e65a6fb30 790 float pa, pb, pc;
onehorse 0:2e5e65a6fb30 791
onehorse 0:2e5e65a6fb30 792 // Auxiliary variables to avoid repeated arithmetic
onehorse 0:2e5e65a6fb30 793 float q1q1 = q1 * q1;
onehorse 0:2e5e65a6fb30 794 float q1q2 = q1 * q2;
onehorse 0:2e5e65a6fb30 795 float q1q3 = q1 * q3;
onehorse 0:2e5e65a6fb30 796 float q1q4 = q1 * q4;
onehorse 0:2e5e65a6fb30 797 float q2q2 = q2 * q2;
onehorse 0:2e5e65a6fb30 798 float q2q3 = q2 * q3;
onehorse 0:2e5e65a6fb30 799 float q2q4 = q2 * q4;
onehorse 0:2e5e65a6fb30 800 float q3q3 = q3 * q3;
onehorse 0:2e5e65a6fb30 801 float q3q4 = q3 * q4;
onehorse 0:2e5e65a6fb30 802 float q4q4 = q4 * q4;
onehorse 0:2e5e65a6fb30 803
onehorse 0:2e5e65a6fb30 804 // Normalise accelerometer measurement
onehorse 0:2e5e65a6fb30 805 norm = sqrt(ax * ax + ay * ay + az * az);
onehorse 0:2e5e65a6fb30 806 if (norm == 0.0f) return; // handle NaN
onehorse 0:2e5e65a6fb30 807 norm = 1.0f / norm; // use reciprocal for division
onehorse 0:2e5e65a6fb30 808 ax *= norm;
onehorse 0:2e5e65a6fb30 809 ay *= norm;
onehorse 0:2e5e65a6fb30 810 az *= norm;
onehorse 0:2e5e65a6fb30 811
onehorse 0:2e5e65a6fb30 812 // Normalise magnetometer measurement
onehorse 0:2e5e65a6fb30 813 norm = sqrt(mx * mx + my * my + mz * mz);
onehorse 0:2e5e65a6fb30 814 if (norm == 0.0f) return; // handle NaN
onehorse 0:2e5e65a6fb30 815 norm = 1.0f / norm; // use reciprocal for division
onehorse 0:2e5e65a6fb30 816 mx *= norm;
onehorse 0:2e5e65a6fb30 817 my *= norm;
onehorse 0:2e5e65a6fb30 818 mz *= norm;
onehorse 0:2e5e65a6fb30 819
onehorse 0:2e5e65a6fb30 820 // Reference direction of Earth's magnetic field
onehorse 0:2e5e65a6fb30 821 hx = 2.0f * mx * (0.5f - q3q3 - q4q4) + 2.0f * my * (q2q3 - q1q4) + 2.0f * mz * (q2q4 + q1q3);
onehorse 0:2e5e65a6fb30 822 hy = 2.0f * mx * (q2q3 + q1q4) + 2.0f * my * (0.5f - q2q2 - q4q4) + 2.0f * mz * (q3q4 - q1q2);
onehorse 0:2e5e65a6fb30 823 bx = sqrt((hx * hx) + (hy * hy));
onehorse 0:2e5e65a6fb30 824 bz = 2.0f * mx * (q2q4 - q1q3) + 2.0f * my * (q3q4 + q1q2) + 2.0f * mz * (0.5f - q2q2 - q3q3);
onehorse 0:2e5e65a6fb30 825
onehorse 0:2e5e65a6fb30 826 // Estimated direction of gravity and magnetic field
onehorse 0:2e5e65a6fb30 827 vx = 2.0f * (q2q4 - q1q3);
onehorse 0:2e5e65a6fb30 828 vy = 2.0f * (q1q2 + q3q4);
onehorse 0:2e5e65a6fb30 829 vz = q1q1 - q2q2 - q3q3 + q4q4;
onehorse 0:2e5e65a6fb30 830 wx = 2.0f * bx * (0.5f - q3q3 - q4q4) + 2.0f * bz * (q2q4 - q1q3);
onehorse 0:2e5e65a6fb30 831 wy = 2.0f * bx * (q2q3 - q1q4) + 2.0f * bz * (q1q2 + q3q4);
onehorse 0:2e5e65a6fb30 832 wz = 2.0f * bx * (q1q3 + q2q4) + 2.0f * bz * (0.5f - q2q2 - q3q3);
onehorse 0:2e5e65a6fb30 833
onehorse 0:2e5e65a6fb30 834 // Error is cross product between estimated direction and measured direction of gravity
onehorse 0:2e5e65a6fb30 835 ex = (ay * vz - az * vy) + (my * wz - mz * wy);
onehorse 0:2e5e65a6fb30 836 ey = (az * vx - ax * vz) + (mz * wx - mx * wz);
onehorse 0:2e5e65a6fb30 837 ez = (ax * vy - ay * vx) + (mx * wy - my * wx);
onehorse 0:2e5e65a6fb30 838 if (Ki > 0.0f)
onehorse 0:2e5e65a6fb30 839 {
onehorse 0:2e5e65a6fb30 840 eInt[0] += ex; // accumulate integral error
onehorse 0:2e5e65a6fb30 841 eInt[1] += ey;
onehorse 0:2e5e65a6fb30 842 eInt[2] += ez;
onehorse 0:2e5e65a6fb30 843 }
onehorse 0:2e5e65a6fb30 844 else
onehorse 0:2e5e65a6fb30 845 {
onehorse 0:2e5e65a6fb30 846 eInt[0] = 0.0f; // prevent integral wind up
onehorse 0:2e5e65a6fb30 847 eInt[1] = 0.0f;
onehorse 0:2e5e65a6fb30 848 eInt[2] = 0.0f;
onehorse 0:2e5e65a6fb30 849 }
onehorse 0:2e5e65a6fb30 850
onehorse 0:2e5e65a6fb30 851 // Apply feedback terms
onehorse 0:2e5e65a6fb30 852 gx = gx + Kp * ex + Ki * eInt[0];
onehorse 0:2e5e65a6fb30 853 gy = gy + Kp * ey + Ki * eInt[1];
onehorse 0:2e5e65a6fb30 854 gz = gz + Kp * ez + Ki * eInt[2];
onehorse 0:2e5e65a6fb30 855
onehorse 0:2e5e65a6fb30 856 // Integrate rate of change of quaternion
onehorse 0:2e5e65a6fb30 857 pa = q2;
onehorse 0:2e5e65a6fb30 858 pb = q3;
onehorse 0:2e5e65a6fb30 859 pc = q4;
onehorse 0:2e5e65a6fb30 860 q1 = q1 + (-q2 * gx - q3 * gy - q4 * gz) * (0.5f * deltat);
onehorse 0:2e5e65a6fb30 861 q2 = pa + (q1 * gx + pb * gz - pc * gy) * (0.5f * deltat);
onehorse 0:2e5e65a6fb30 862 q3 = pb + (q1 * gy - pa * gz + pc * gx) * (0.5f * deltat);
onehorse 0:2e5e65a6fb30 863 q4 = pc + (q1 * gz + pa * gy - pb * gx) * (0.5f * deltat);
onehorse 0:2e5e65a6fb30 864
onehorse 0:2e5e65a6fb30 865 // Normalise quaternion
onehorse 0:2e5e65a6fb30 866 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);
onehorse 0:2e5e65a6fb30 867 norm = 1.0f / norm;
onehorse 0:2e5e65a6fb30 868 q[0] = q1 * norm;
onehorse 0:2e5e65a6fb30 869 q[1] = q2 * norm;
onehorse 0:2e5e65a6fb30 870 q[2] = q3 * norm;
onehorse 0:2e5e65a6fb30 871 q[3] = q4 * norm;
onehorse 0:2e5e65a6fb30 872
onehorse 0:2e5e65a6fb30 873 }
onehorse 0:2e5e65a6fb30 874 };
onehorse 0:2e5e65a6fb30 875 #endif