Library for the MPU9250 9DOF IMU chip.

Dependents:   Xadow-M0_Xadow-OLED_Accelerometer MARe_VT_ble_PeakSearch_Kalman_Inativ

Committer:
ruevs
Date:
Fri Mar 01 09:47:40 2019 +0000
Revision:
1:fc94c7336b7c
Parent:
0:2315cd1878a1
Add buffers needed for magnetometer calibration.

Who changed what in which revision?

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