Dependencies:   mbed Servo PID

Committer:
omar28744
Date:
Fri May 10 08:45:41 2019 +0000
Revision:
0:cf5854b3296f
localization program

Who changed what in which revision?

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