B16

Dependencies:   mbed

Committer:
57340500084
Date:
Wed Dec 09 02:50:22 2015 +0000
Revision:
0:b0ed3674f5b2
16B

Who changed what in which revision?

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