thanks to Zoltan Hudak publish the way to use stm32f103c8t6 on mbed. now you can use it with MPC4725 DAC

Dependencies:   mbed-STM32F103C8T6 mbed

Fork of Wii_IRCam_Test by Michael Shimniok

Committer:
Zeran
Date:
Thu May 25 16:49:26 2017 +0000
Revision:
3:37fb1e2aacf3
STM32f103c8t6 work with GY91(mpu9250 only on bmp280) Example

Who changed what in which revision?

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