Fork of MPU6050IMU by Austin Buchan

Committer:
yxyang
Date:
Tue May 30 06:42:08 2017 +0000
Revision:
4:095b126178df
Parent:
3:359efdec694f

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
onehorse 1:cea9d83b8636 1 #ifndef MPU6050_H
onehorse 1:cea9d83b8636 2 #define MPU6050_H
yxyang 4:095b126178df 3
onehorse 1:cea9d83b8636 4 #include "math.h"
yxyang 4:095b126178df 5 #include "mbed.h"
yxyang 4:095b126178df 6
yxyang 4:095b126178df 7 // Define registers per MPU6050, Register Map and Descriptions, Rev 4.2,
yxyang 4:095b126178df 8 // 08/19/2013 6 DOF Motion sensor fusion device
onehorse 1:cea9d83b8636 9 // Invensense Inc., www.invensense.com
yxyang 4:095b126178df 10 // See also MPU-6050 Register Map and Descriptions, Revision 4.0,
yxyang 4:095b126178df 11 // RM-MPU-6050A-00, 9/12/2012 for registers not listed in
yxyang 4:095b126178df 12 // above document; the MPU6050 and MPU 9150 are virtually identical but the
yxyang 4:095b126178df 13 // latter has an on-board magnetic sensor
onehorse 1:cea9d83b8636 14 //
yxyang 4:095b126178df 15 #define XGOFFS_TC \
yxyang 4:095b126178df 16 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD
yxyang 4:095b126178df 17 #define YGOFFS_TC 0x01
yxyang 4:095b126178df 18 #define ZGOFFS_TC 0x02
yxyang 4:095b126178df 19 #define X_FINE_GAIN 0x03 // [7:0] fine gain
yxyang 4:095b126178df 20 #define Y_FINE_GAIN 0x04
yxyang 4:095b126178df 21 #define Z_FINE_GAIN 0x05
yxyang 4:095b126178df 22 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer
yxyang 4:095b126178df 23 #define XA_OFFSET_L_TC 0x07
yxyang 4:095b126178df 24 #define YA_OFFSET_H 0x08
yxyang 4:095b126178df 25 #define YA_OFFSET_L_TC 0x09
yxyang 4:095b126178df 26 #define ZA_OFFSET_H 0x0A
yxyang 4:095b126178df 27 #define ZA_OFFSET_L_TC 0x0B
yxyang 4:095b126178df 28 #define SELF_TEST_X 0x0D
yxyang 4:095b126178df 29 #define SELF_TEST_Y 0x0E
yxyang 4:095b126178df 30 #define SELF_TEST_Z 0x0F
yxyang 4:095b126178df 31 #define SELF_TEST_A 0x10
yxyang 4:095b126178df 32 #define XG_OFFS_USRH \
yxyang 4:095b126178df 33 0x13 // User-defined trim values for gyroscope; supported in MPU-6050?
yxyang 4:095b126178df 34 #define XG_OFFS_USRL 0x14
yxyang 4:095b126178df 35 #define YG_OFFS_USRH 0x15
yxyang 4:095b126178df 36 #define YG_OFFS_USRL 0x16
yxyang 4:095b126178df 37 #define ZG_OFFS_USRH 0x17
yxyang 4:095b126178df 38 #define ZG_OFFS_USRL 0x18
yxyang 4:095b126178df 39 #define SMPLRT_DIV 0x19
yxyang 4:095b126178df 40 #define CONFIG 0x1A
yxyang 4:095b126178df 41 #define GYRO_CONFIG 0x1B
yxyang 4:095b126178df 42 #define ACCEL_CONFIG 0x1C
yxyang 4:095b126178df 43 #define FF_THR 0x1D // Free-fall
yxyang 4:095b126178df 44 #define FF_DUR 0x1E // Free-fall
yxyang 4:095b126178df 45 #define MOT_THR 0x1F // Motion detection threshold bits [7:0]
yxyang 4:095b126178df 46 #define MOT_DUR \
yxyang 4:095b126178df 47 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz
yxyang 4:095b126178df 48 // rate, LSB = 1 ms
yxyang 4:095b126178df 49 #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0]
yxyang 4:095b126178df 50 #define ZRMOT_DUR \
yxyang 4:095b126178df 51 0x22 // Duration counter threshold for zero motion interrupt generation, 16
yxyang 4:095b126178df 52 // Hz rate, LSB = 64 ms
yxyang 4:095b126178df 53 #define FIFO_EN 0x23
yxyang 4:095b126178df 54 #define I2C_MST_CTRL 0x24
yxyang 4:095b126178df 55 #define I2C_SLV0_ADDR 0x25
yxyang 4:095b126178df 56 #define I2C_SLV0_REG 0x26
yxyang 4:095b126178df 57 #define I2C_SLV0_CTRL 0x27
yxyang 4:095b126178df 58 #define I2C_SLV1_ADDR 0x28
yxyang 4:095b126178df 59 #define I2C_SLV1_REG 0x29
yxyang 4:095b126178df 60 #define I2C_SLV1_CTRL 0x2A
yxyang 4:095b126178df 61 #define I2C_SLV2_ADDR 0x2B
yxyang 4:095b126178df 62 #define I2C_SLV2_REG 0x2C
yxyang 4:095b126178df 63 #define I2C_SLV2_CTRL 0x2D
yxyang 4:095b126178df 64 #define I2C_SLV3_ADDR 0x2E
yxyang 4:095b126178df 65 #define I2C_SLV3_REG 0x2F
yxyang 4:095b126178df 66 #define I2C_SLV3_CTRL 0x30
yxyang 4:095b126178df 67 #define I2C_SLV4_ADDR 0x31
yxyang 4:095b126178df 68 #define I2C_SLV4_REG 0x32
yxyang 4:095b126178df 69 #define I2C_SLV4_DO 0x33
yxyang 4:095b126178df 70 #define I2C_SLV4_CTRL 0x34
yxyang 4:095b126178df 71 #define I2C_SLV4_DI 0x35
yxyang 4:095b126178df 72 #define I2C_MST_STATUS 0x36
yxyang 4:095b126178df 73 #define INT_PIN_CFG 0x37
yxyang 4:095b126178df 74 #define INT_ENABLE 0x38
yxyang 4:095b126178df 75 #define DMP_INT_STATUS 0x39 // Check DMP interrupt
yxyang 4:095b126178df 76 #define INT_STATUS 0x3A
yxyang 4:095b126178df 77 #define ACCEL_XOUT_H 0x3B
yxyang 4:095b126178df 78 #define ACCEL_XOUT_L 0x3C
yxyang 4:095b126178df 79 #define ACCEL_YOUT_H 0x3D
yxyang 4:095b126178df 80 #define ACCEL_YOUT_L 0x3E
yxyang 4:095b126178df 81 #define ACCEL_ZOUT_H 0x3F
yxyang 4:095b126178df 82 #define ACCEL_ZOUT_L 0x40
yxyang 4:095b126178df 83 #define TEMP_OUT_H 0x41
yxyang 4:095b126178df 84 #define TEMP_OUT_L 0x42
yxyang 4:095b126178df 85 #define GYRO_XOUT_H 0x43
yxyang 4:095b126178df 86 #define GYRO_XOUT_L 0x44
yxyang 4:095b126178df 87 #define GYRO_YOUT_H 0x45
yxyang 4:095b126178df 88 #define GYRO_YOUT_L 0x46
yxyang 4:095b126178df 89 #define GYRO_ZOUT_H 0x47
yxyang 4:095b126178df 90 #define GYRO_ZOUT_L 0x48
onehorse 1:cea9d83b8636 91 #define EXT_SENS_DATA_00 0x49
onehorse 1:cea9d83b8636 92 #define EXT_SENS_DATA_01 0x4A
onehorse 1:cea9d83b8636 93 #define EXT_SENS_DATA_02 0x4B
onehorse 1:cea9d83b8636 94 #define EXT_SENS_DATA_03 0x4C
onehorse 1:cea9d83b8636 95 #define EXT_SENS_DATA_04 0x4D
onehorse 1:cea9d83b8636 96 #define EXT_SENS_DATA_05 0x4E
onehorse 1:cea9d83b8636 97 #define EXT_SENS_DATA_06 0x4F
onehorse 1:cea9d83b8636 98 #define EXT_SENS_DATA_07 0x50
onehorse 1:cea9d83b8636 99 #define EXT_SENS_DATA_08 0x51
onehorse 1:cea9d83b8636 100 #define EXT_SENS_DATA_09 0x52
onehorse 1:cea9d83b8636 101 #define EXT_SENS_DATA_10 0x53
onehorse 1:cea9d83b8636 102 #define EXT_SENS_DATA_11 0x54
onehorse 1:cea9d83b8636 103 #define EXT_SENS_DATA_12 0x55
onehorse 1:cea9d83b8636 104 #define EXT_SENS_DATA_13 0x56
onehorse 1:cea9d83b8636 105 #define EXT_SENS_DATA_14 0x57
onehorse 1:cea9d83b8636 106 #define EXT_SENS_DATA_15 0x58
onehorse 1:cea9d83b8636 107 #define EXT_SENS_DATA_16 0x59
onehorse 1:cea9d83b8636 108 #define EXT_SENS_DATA_17 0x5A
onehorse 1:cea9d83b8636 109 #define EXT_SENS_DATA_18 0x5B
onehorse 1:cea9d83b8636 110 #define EXT_SENS_DATA_19 0x5C
onehorse 1:cea9d83b8636 111 #define EXT_SENS_DATA_20 0x5D
onehorse 1:cea9d83b8636 112 #define EXT_SENS_DATA_21 0x5E
onehorse 1:cea9d83b8636 113 #define EXT_SENS_DATA_22 0x5F
onehorse 1:cea9d83b8636 114 #define EXT_SENS_DATA_23 0x60
onehorse 1:cea9d83b8636 115 #define MOT_DETECT_STATUS 0x61
yxyang 4:095b126178df 116 #define I2C_SLV0_DO 0x63
yxyang 4:095b126178df 117 #define I2C_SLV1_DO 0x64
yxyang 4:095b126178df 118 #define I2C_SLV2_DO 0x65
yxyang 4:095b126178df 119 #define I2C_SLV3_DO 0x66
onehorse 1:cea9d83b8636 120 #define I2C_MST_DELAY_CTRL 0x67
yxyang 4:095b126178df 121 #define SIGNAL_PATH_RESET 0x68
yxyang 4:095b126178df 122 #define MOT_DETECT_CTRL 0x69
yxyang 4:095b126178df 123 #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP
yxyang 4:095b126178df 124 #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode
yxyang 4:095b126178df 125 #define PWR_MGMT_2 0x6C
yxyang 4:095b126178df 126 #define DMP_BANK 0x6D // Activates a specific bank in the DMP
yxyang 4:095b126178df 127 #define DMP_RW_PNT \
yxyang 4:095b126178df 128 0x6E // Set read/write pointer to a specific start address in specified DMP
yxyang 4:095b126178df 129 // bank
yxyang 4:095b126178df 130 #define DMP_REG 0x6F // Register in DMP from which to read or to which to write
yxyang 4:095b126178df 131 #define DMP_REG_1 0x70
yxyang 4:095b126178df 132 #define DMP_REG_2 0x71
yxyang 4:095b126178df 133 #define FIFO_COUNTH 0x72
yxyang 4:095b126178df 134 #define FIFO_COUNTL 0x73
yxyang 4:095b126178df 135 #define FIFO_R_W 0x74
onehorse 1:cea9d83b8636 136 #define WHO_AM_I_MPU6050 0x75 // Should return 0x68
onehorse 1:cea9d83b8636 137
yxyang 4:095b126178df 138 // Using the GY-521 breakout board, I set ADO to 0 by grounding through a 4k7
yxyang 4:095b126178df 139 // resistor
onehorse 1:cea9d83b8636 140 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1
onehorse 1:cea9d83b8636 141 #define ADO 0
onehorse 1:cea9d83b8636 142 #if ADO
yxyang 4:095b126178df 143 #define MPU6050_ADDRESS 0x69 << 1 // Device address when ADO = 1
onehorse 1:cea9d83b8636 144 #else
yxyang 4:095b126178df 145 #define MPU6050_ADDRESS 0x68 << 1 // Device address when ADO = 0
onehorse 1:cea9d83b8636 146 #endif
onehorse 1:cea9d83b8636 147
onehorse 1:cea9d83b8636 148 // Set initial input parameters
yxyang 4:095b126178df 149 enum Ascale
yxyang 4:095b126178df 150 {
onehorse 1:cea9d83b8636 151 AFS_2G = 0,
onehorse 1:cea9d83b8636 152 AFS_4G,
onehorse 1:cea9d83b8636 153 AFS_8G,
onehorse 1:cea9d83b8636 154 AFS_16G
onehorse 1:cea9d83b8636 155 };
onehorse 1:cea9d83b8636 156
yxyang 4:095b126178df 157 enum Gscale
yxyang 4:095b126178df 158 {
onehorse 1:cea9d83b8636 159 GFS_250DPS = 0,
onehorse 1:cea9d83b8636 160 GFS_500DPS,
onehorse 1:cea9d83b8636 161 GFS_1000DPS,
onehorse 1:cea9d83b8636 162 GFS_2000DPS
onehorse 1:cea9d83b8636 163 };
onehorse 1:cea9d83b8636 164
onehorse 1:cea9d83b8636 165 // Specify sensor full scale
onehorse 1:cea9d83b8636 166 int Gscale = GFS_250DPS;
onehorse 1:cea9d83b8636 167 int Ascale = AFS_2G;
onehorse 1:cea9d83b8636 168
yxyang 4:095b126178df 169 // Set up I2C, (SDA,SCL)
abuchan 3:359efdec694f 170 #define MPU_SDA p9
abuchan 3:359efdec694f 171 #define MPU_SCL p10
yxyang 4:095b126178df 172 I2C i2c (MPU_SDA, MPU_SCL);
onehorse 1:cea9d83b8636 173
yxyang 4:095b126178df 174 // DigitalOut myled(LED1);
yxyang 4:095b126178df 175
onehorse 1:cea9d83b8636 176 float aRes, gRes; // scale resolutions per LSB for the sensors
yxyang 4:095b126178df 177
onehorse 1:cea9d83b8636 178 // Pin definitions
yxyang 4:095b126178df 179 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins
onehorse 1:cea9d83b8636 180
yxyang 4:095b126178df 181 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output
yxyang 4:095b126178df 182 float ax, ay, az; // Stores the real accel value in g's
yxyang 4:095b126178df 183 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output
yxyang 4:095b126178df 184 float gx, gy, gz; // Stores the real gyro value in degrees per seconds
yxyang 4:095b126178df 185 float gyroBias[3] = { 0, 0, 0 },
yxyang 4:095b126178df 186 accelBias[3]
yxyang 4:095b126178df 187 = { 0, 0, 0 }; // Bias corrections for gyro and accelerometer
yxyang 4:095b126178df 188 int16_t
yxyang 4:095b126178df 189 tempCount; // Stores the real internal chip temperature in degrees Celsius
onehorse 1:cea9d83b8636 190 float temperature;
onehorse 1:cea9d83b8636 191 float SelfTest[6];
onehorse 1:cea9d83b8636 192
onehorse 1:cea9d83b8636 193 int delt_t = 0; // used to control display output rate
onehorse 1:cea9d83b8636 194 int count = 0; // used to control display output rate
onehorse 1:cea9d83b8636 195
onehorse 1:cea9d83b8636 196 // parameters for 6 DoF sensor fusion calculations
onehorse 1:cea9d83b8636 197 float PI = 3.14159265358979323846f;
yxyang 4:095b126178df 198 float GyroMeasError = PI * (60.0f / 180.0f); // gyroscope measurement error in
yxyang 4:095b126178df 199 // rads/s (start at 60 deg/s),
yxyang 4:095b126178df 200 // then reduce after ~10 s to 3
yxyang 4:095b126178df 201 float beta = sqrt (3.0f / 4.0f) * GyroMeasError; // compute beta
yxyang 4:095b126178df 202 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in
yxyang 4:095b126178df 203 // rad/s/s (start at 0.0 deg/s/s)
yxyang 4:095b126178df 204 float zeta = sqrt (3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other
yxyang 4:095b126178df 205 // free parameter in the
yxyang 4:095b126178df 206 // Madgwick scheme usually set
yxyang 4:095b126178df 207 // to a small or zero value
onehorse 1:cea9d83b8636 208 float pitch, yaw, roll;
yxyang 4:095b126178df 209 float deltat = 0.0f; // integration interval for both filter schemes
yxyang 4:095b126178df 210 int lastUpdate = 0, firstUpdate = 0,
yxyang 4:095b126178df 211 Now = 0; // used to calculate integration interval
yxyang 4:095b126178df 212 // // used to calculate integration interval
yxyang 4:095b126178df 213 float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f }; // vector to hold quaternion
onehorse 1:cea9d83b8636 214
yxyang 4:095b126178df 215 class MPU6050
yxyang 4:095b126178df 216 {
yxyang 4:095b126178df 217
yxyang 4:095b126178df 218 protected:
yxyang 4:095b126178df 219 public:
onehorse 1:cea9d83b8636 220 //===================================================================================================================
yxyang 4:095b126178df 221 //====== Set of useful function to access acceleratio, gyroscope, and
yxyang 4:095b126178df 222 // temperature data
yxyang 4:095b126178df 223 //===================================================================================================================
onehorse 1:cea9d83b8636 224
yxyang 4:095b126178df 225 void
yxyang 4:095b126178df 226 writeByte (uint8_t address, uint8_t subAddress, uint8_t data)
yxyang 4:095b126178df 227 {
yxyang 4:095b126178df 228 char data_write[2];
yxyang 4:095b126178df 229 data_write[0] = subAddress;
yxyang 4:095b126178df 230 data_write[1] = data;
yxyang 4:095b126178df 231 i2c.write (address, data_write, 2, 0);
yxyang 4:095b126178df 232 }
onehorse 1:cea9d83b8636 233
yxyang 4:095b126178df 234 char
yxyang 4:095b126178df 235 readByte (uint8_t address, uint8_t subAddress)
yxyang 4:095b126178df 236 {
yxyang 4:095b126178df 237 char data[1]; // `data` will store the register data
onehorse 1:cea9d83b8636 238 char data_write[1];
onehorse 1:cea9d83b8636 239 data_write[0] = subAddress;
yxyang 4:095b126178df 240 i2c.write (address, data_write, 1, 1); // no stop
yxyang 4:095b126178df 241 i2c.read (address, data, 1, 0);
yxyang 4:095b126178df 242 return data[0];
yxyang 4:095b126178df 243 }
onehorse 1:cea9d83b8636 244
yxyang 4:095b126178df 245 void
yxyang 4:095b126178df 246 readBytes (uint8_t address, uint8_t subAddress, uint8_t count, uint8_t *dest)
yxyang 4:095b126178df 247 {
onehorse 1:cea9d83b8636 248 char data[14];
onehorse 1:cea9d83b8636 249 char data_write[1];
onehorse 1:cea9d83b8636 250 data_write[0] = subAddress;
yxyang 4:095b126178df 251 i2c.write (address, data_write, 1, 1); // no stop
yxyang 4:095b126178df 252 i2c.read (address, data, count, 0);
yxyang 4:095b126178df 253 for (int ii = 0; ii < count; ii++)
yxyang 4:095b126178df 254 {
yxyang 4:095b126178df 255 dest[ii] = data[ii];
yxyang 4:095b126178df 256 }
yxyang 4:095b126178df 257 }
onehorse 1:cea9d83b8636 258
yxyang 4:095b126178df 259 void
yxyang 4:095b126178df 260 getGres ()
onehorse 1:cea9d83b8636 261 {
yxyang 4:095b126178df 262 switch (Gscale)
yxyang 4:095b126178df 263 {
yxyang 4:095b126178df 264 // Possible gyro scales (and their register bit settings) are:
yxyang 4:095b126178df 265 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11).
yxyang 4:095b126178df 266 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that
yxyang 4:095b126178df 267 // 2-bit value:
yxyang 4:095b126178df 268 case GFS_250DPS:
yxyang 4:095b126178df 269 gRes = 250.0 / 32768.0;
yxyang 4:095b126178df 270 break;
yxyang 4:095b126178df 271 case GFS_500DPS:
yxyang 4:095b126178df 272 gRes = 500.0 / 32768.0;
yxyang 4:095b126178df 273 break;
yxyang 4:095b126178df 274 case GFS_1000DPS:
yxyang 4:095b126178df 275 gRes = 1000.0 / 32768.0;
yxyang 4:095b126178df 276 break;
yxyang 4:095b126178df 277 case GFS_2000DPS:
yxyang 4:095b126178df 278 gRes = 2000.0 / 32768.0;
yxyang 4:095b126178df 279 break;
yxyang 4:095b126178df 280 }
onehorse 1:cea9d83b8636 281 }
onehorse 1:cea9d83b8636 282
yxyang 4:095b126178df 283 void
yxyang 4:095b126178df 284 getAres ()
yxyang 4:095b126178df 285 {
yxyang 4:095b126178df 286 switch (Ascale)
yxyang 4:095b126178df 287 {
yxyang 4:095b126178df 288 // Possible accelerometer scales (and their register bit settings) are:
yxyang 4:095b126178df 289 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11).
yxyang 4:095b126178df 290 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that
yxyang 4:095b126178df 291 // 2-bit value:
yxyang 4:095b126178df 292 case AFS_2G:
yxyang 4:095b126178df 293 aRes = 2.0 / 32768.0;
yxyang 4:095b126178df 294 break;
yxyang 4:095b126178df 295 case AFS_4G:
yxyang 4:095b126178df 296 aRes = 4.0 / 32768.0;
yxyang 4:095b126178df 297 break;
yxyang 4:095b126178df 298 case AFS_8G:
yxyang 4:095b126178df 299 aRes = 8.0 / 32768.0;
yxyang 4:095b126178df 300 break;
yxyang 4:095b126178df 301 case AFS_16G:
yxyang 4:095b126178df 302 aRes = 16.0 / 32768.0;
yxyang 4:095b126178df 303 break;
yxyang 4:095b126178df 304 }
yxyang 4:095b126178df 305 }
onehorse 1:cea9d83b8636 306
yxyang 4:095b126178df 307 void
yxyang 4:095b126178df 308 readAccelData (int16_t *destination)
yxyang 4:095b126178df 309 {
yxyang 4:095b126178df 310 uint8_t rawData[6]; // x/y/z accel register data stored here
yxyang 4:095b126178df 311 readBytes (MPU6050_ADDRESS, ACCEL_XOUT_H, 6,
yxyang 4:095b126178df 312 &rawData[0]); // Read the six raw data registers into data array
yxyang 4:095b126178df 313 destination[0] = (int16_t) (
yxyang 4:095b126178df 314 ((int16_t)rawData[0] << 8)
yxyang 4:095b126178df 315 | rawData[1]); // Turn the MSB and LSB into a signed 16-bit value
yxyang 4:095b126178df 316 destination[1] = (int16_t) (((int16_t)rawData[2] << 8) | rawData[3]);
yxyang 4:095b126178df 317 destination[2] = (int16_t) (((int16_t)rawData[4] << 8) | rawData[5]);
yxyang 4:095b126178df 318 }
onehorse 1:cea9d83b8636 319
yxyang 4:095b126178df 320 void
yxyang 4:095b126178df 321 readGyroData (int16_t *destination)
yxyang 4:095b126178df 322 {
yxyang 4:095b126178df 323 uint8_t rawData[6]; // x/y/z gyro register data stored here
yxyang 4:095b126178df 324 readBytes (MPU6050_ADDRESS, GYRO_XOUT_H, 6,
yxyang 4:095b126178df 325 &rawData[0]); // Read the six raw data registers sequentially
yxyang 4:095b126178df 326 // into data array
yxyang 4:095b126178df 327 destination[0] = (int16_t) (
yxyang 4:095b126178df 328 ((int16_t)rawData[0] << 8)
yxyang 4:095b126178df 329 | rawData[1]); // Turn the MSB and LSB into a signed 16-bit value
yxyang 4:095b126178df 330 destination[1] = (int16_t) (((int16_t)rawData[2] << 8) | rawData[3]);
yxyang 4:095b126178df 331 destination[2] = (int16_t) (((int16_t)rawData[4] << 8) | rawData[5]);
yxyang 4:095b126178df 332 }
onehorse 1:cea9d83b8636 333
yxyang 4:095b126178df 334 int16_t
yxyang 4:095b126178df 335 readTempData ()
yxyang 4:095b126178df 336 {
yxyang 4:095b126178df 337 uint8_t rawData[2]; // x/y/z gyro register data stored here
yxyang 4:095b126178df 338 readBytes (MPU6050_ADDRESS, TEMP_OUT_H, 2,
yxyang 4:095b126178df 339 &rawData[0]); // Read the two raw data registers sequentially
yxyang 4:095b126178df 340 // into data array
yxyang 4:095b126178df 341 return (int16_t) (
yxyang 4:095b126178df 342 ((int16_t)rawData[0]) << 8
yxyang 4:095b126178df 343 | rawData[1]); // Turn the MSB and LSB into a 16-bit value
yxyang 4:095b126178df 344 }
yxyang 4:095b126178df 345
yxyang 4:095b126178df 346 // Configure the motion detection control for low power accelerometer mode
yxyang 4:095b126178df 347 void
yxyang 4:095b126178df 348 LowPowerAccelOnly ()
yxyang 4:095b126178df 349 {
onehorse 1:cea9d83b8636 350
yxyang 4:095b126178df 351 // The sensor has a high-pass filter necessary to invoke to allow the
yxyang 4:095b126178df 352 // sensor motion detection algorithms work properly
yxyang 4:095b126178df 353 // Motion detection occurs on free-fall (acceleration below a threshold for
yxyang 4:095b126178df 354 // some time for all axes), motion (acceleration
yxyang 4:095b126178df 355 // above a threshold for some time on at least one axis), and zero-motion
yxyang 4:095b126178df 356 // toggle (acceleration on each axis less than a
yxyang 4:095b126178df 357 // threshold for some time sets this flag, motion above the threshold turns
yxyang 4:095b126178df 358 // it off). The high-pass filter takes gravity out
yxyang 4:095b126178df 359 // consideration for these threshold evaluations; otherwise, the flags
yxyang 4:095b126178df 360 // would be set all the time!
onehorse 1:cea9d83b8636 361
yxyang 4:095b126178df 362 uint8_t c = readByte (MPU6050_ADDRESS, PWR_MGMT_1);
yxyang 4:095b126178df 363 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 364 c & ~0x30); // Clear sleep and cycle bits [5:6]
yxyang 4:095b126178df 365 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 366 c | 0x30); // Set sleep and cycle bits [5:6] to zero to make
yxyang 4:095b126178df 367 // sure accelerometer is running
onehorse 1:cea9d83b8636 368
yxyang 4:095b126178df 369 c = readByte (MPU6050_ADDRESS, PWR_MGMT_2);
yxyang 4:095b126178df 370 writeByte (MPU6050_ADDRESS, PWR_MGMT_2,
yxyang 4:095b126178df 371 c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5]
yxyang 4:095b126178df 372 writeByte (MPU6050_ADDRESS, PWR_MGMT_2,
yxyang 4:095b126178df 373 c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure
yxyang 4:095b126178df 374 // accelerometer is running
onehorse 1:cea9d83b8636 375
yxyang 4:095b126178df 376 c = readByte (MPU6050_ADDRESS, ACCEL_CONFIG);
yxyang 4:095b126178df 377 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 378 c & ~0x07); // Clear high-pass filter bits [2:0]
yxyang 4:095b126178df 379 // Set high-pass filter to 0) reset (disable), 1) 5 Hz, 2) 2.5 Hz, 3) 1.25
yxyang 4:095b126178df 380 // Hz, 4) 0.63 Hz, or 7) Hold
yxyang 4:095b126178df 381 writeByte (
yxyang 4:095b126178df 382 MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 383 c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter
onehorse 1:cea9d83b8636 384
yxyang 4:095b126178df 385 c = readByte (MPU6050_ADDRESS, CONFIG);
yxyang 4:095b126178df 386 writeByte (MPU6050_ADDRESS, CONFIG,
yxyang 4:095b126178df 387 c & ~0x07); // Clear low-pass filter bits [2:0]
yxyang 4:095b126178df 388 writeByte (MPU6050_ADDRESS, CONFIG,
yxyang 4:095b126178df 389 c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate
yxyang 4:095b126178df 390
yxyang 4:095b126178df 391 c = readByte (MPU6050_ADDRESS, INT_ENABLE);
yxyang 4:095b126178df 392 writeByte (MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts
yxyang 4:095b126178df 393 writeByte (MPU6050_ADDRESS, INT_ENABLE,
yxyang 4:095b126178df 394 0x40); // Enable motion threshold (bits 5) interrupt only
onehorse 1:cea9d83b8636 395
yxyang 4:095b126178df 396 // Motion detection interrupt requires the absolute value of any axis to
yxyang 4:095b126178df 397 // lie above the detection threshold
yxyang 4:095b126178df 398 // for at least the counter duration
yxyang 4:095b126178df 399 writeByte (MPU6050_ADDRESS, MOT_THR,
yxyang 4:095b126178df 400 0x80); // Set motion detection to 0.256 g; LSB = 2 mg
yxyang 4:095b126178df 401 writeByte (
yxyang 4:095b126178df 402 MPU6050_ADDRESS, MOT_DUR,
yxyang 4:095b126178df 403 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate
yxyang 4:095b126178df 404
yxyang 4:095b126178df 405 wait (0.1); // Add delay for accumulation of samples
onehorse 1:cea9d83b8636 406
yxyang 4:095b126178df 407 c = readByte (MPU6050_ADDRESS, ACCEL_CONFIG);
yxyang 4:095b126178df 408 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 409 c & ~0x07); // Clear high-pass filter bits [2:0]
yxyang 4:095b126178df 410 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7;
yxyang 4:095b126178df 411 // hold the initial
yxyang 4:095b126178df 412 // accleration value
yxyang 4:095b126178df 413 // as a referance
yxyang 4:095b126178df 414
yxyang 4:095b126178df 415 c = readByte (MPU6050_ADDRESS, PWR_MGMT_2);
yxyang 4:095b126178df 416 writeByte (MPU6050_ADDRESS, PWR_MGMT_2,
yxyang 4:095b126178df 417 c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and
yxyang 4:095b126178df 418 // LP_WAKE_CTRL bits [6:7]
yxyang 4:095b126178df 419 writeByte (MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency
yxyang 4:095b126178df 420 // to 5 Hz, and disable
yxyang 4:095b126178df 421 // XG, YG, and ZG gyros
yxyang 4:095b126178df 422 // (bits [0:2])
onehorse 1:cea9d83b8636 423
yxyang 4:095b126178df 424 c = readByte (MPU6050_ADDRESS, PWR_MGMT_1);
yxyang 4:095b126178df 425 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 426 c & ~0x20); // Clear sleep and cycle bit 5
yxyang 4:095b126178df 427 writeByte (MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to
yxyang 4:095b126178df 428 // begin low power
yxyang 4:095b126178df 429 // accelerometer motion
yxyang 4:095b126178df 430 // interrupts
yxyang 4:095b126178df 431 }
yxyang 4:095b126178df 432
yxyang 4:095b126178df 433 void
yxyang 4:095b126178df 434 resetMPU6050 ()
yxyang 4:095b126178df 435 {
yxyang 4:095b126178df 436 // reset device
yxyang 4:095b126178df 437 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 438 0x80); // Write a one to bit 7 reset bit; toggle reset device
yxyang 4:095b126178df 439 wait (0.1);
yxyang 4:095b126178df 440 }
yxyang 4:095b126178df 441
yxyang 4:095b126178df 442 void
yxyang 4:095b126178df 443 initMPU6050 ()
yxyang 4:095b126178df 444 {
yxyang 4:095b126178df 445 // Initialize MPU6050 device
yxyang 4:095b126178df 446 // wake up device
yxyang 4:095b126178df 447 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 448 0x00); // Clear sleep mode bit (6), enable all sensors
yxyang 4:095b126178df 449 wait (0.1); // Delay 100 ms for PLL to get established on x-axis gyro;
yxyang 4:095b126178df 450 // should check for PLL ready interrupt
yxyang 4:095b126178df 451
yxyang 4:095b126178df 452 // get stable time source
yxyang 4:095b126178df 453 writeByte (MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be
yxyang 4:095b126178df 454 // PLL with x-axis gyroscope
yxyang 4:095b126178df 455 // reference, bits 2:0 = 001
onehorse 1:cea9d83b8636 456
yxyang 4:095b126178df 457 // Configure Gyro and Accelerometer
yxyang 4:095b126178df 458 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz,
yxyang 4:095b126178df 459 // respectively;
yxyang 4:095b126178df 460 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
yxyang 4:095b126178df 461 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
yxyang 4:095b126178df 462 writeByte (MPU6050_ADDRESS, CONFIG, 0x03);
yxyang 4:095b126178df 463
yxyang 4:095b126178df 464 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
yxyang 4:095b126178df 465 writeByte (MPU6050_ADDRESS, SMPLRT_DIV,
yxyang 4:095b126178df 466 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above
onehorse 1:cea9d83b8636 467
yxyang 4:095b126178df 468 // Set gyroscope full scale range
yxyang 4:095b126178df 469 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are
yxyang 4:095b126178df 470 // left-shifted into positions 4:3
yxyang 4:095b126178df 471 uint8_t c = readByte (MPU6050_ADDRESS, GYRO_CONFIG);
yxyang 4:095b126178df 472 writeByte (MPU6050_ADDRESS, GYRO_CONFIG,
yxyang 4:095b126178df 473 c & ~0xE0); // Clear self-test bits [7:5]
yxyang 4:095b126178df 474 writeByte (MPU6050_ADDRESS, GYRO_CONFIG,
yxyang 4:095b126178df 475 c & ~0x18); // Clear AFS bits [4:3]
yxyang 4:095b126178df 476 writeByte (MPU6050_ADDRESS, GYRO_CONFIG,
yxyang 4:095b126178df 477 c | Gscale << 3); // Set full scale range for the gyro
onehorse 1:cea9d83b8636 478
yxyang 4:095b126178df 479 // Set accelerometer configuration
yxyang 4:095b126178df 480 c = readByte (MPU6050_ADDRESS, ACCEL_CONFIG);
yxyang 4:095b126178df 481 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 482 c & ~0xE0); // Clear self-test bits [7:5]
yxyang 4:095b126178df 483 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 484 c & ~0x18); // Clear AFS bits [4:3]
yxyang 4:095b126178df 485 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 486 c | Ascale << 3); // Set full scale range for the accelerometer
onehorse 1:cea9d83b8636 487
yxyang 4:095b126178df 488 // Configure Interrupts and Bypass Enable
yxyang 4:095b126178df 489 // Set interrupt pin active high, push-pull, and clear on read of
yxyang 4:095b126178df 490 // INT_STATUS, enable I2C_BYPASS_EN so additional chips
yxyang 4:095b126178df 491 // can join the I2C bus and all can be controlled by the Arduino as master
yxyang 4:095b126178df 492 writeByte (MPU6050_ADDRESS, INT_PIN_CFG, 0x22);
yxyang 4:095b126178df 493 writeByte (MPU6050_ADDRESS, INT_ENABLE,
yxyang 4:095b126178df 494 0x01); // Enable data ready (bit 0) interrupt
onehorse 1:cea9d83b8636 495 }
onehorse 1:cea9d83b8636 496
yxyang 4:095b126178df 497 // Function which accumulates gyro and accelerometer data after device
yxyang 4:095b126178df 498 // initialization. It calculates the average
yxyang 4:095b126178df 499 // of the at-rest readings and then loads the resulting offsets into
yxyang 4:095b126178df 500 // accelerometer and gyro bias registers.
yxyang 4:095b126178df 501 void
yxyang 4:095b126178df 502 calibrateMPU6050 (float *dest1, float *dest2)
yxyang 4:095b126178df 503 {
yxyang 4:095b126178df 504 uint8_t
yxyang 4:095b126178df 505 data[12]; // data array to hold accelerometer and gyro x, y, z, data
yxyang 4:095b126178df 506 uint16_t ii, packet_count, fifo_count;
yxyang 4:095b126178df 507 int32_t gyro_bias[3] = { 0, 0, 0 }, accel_bias[3] = { 0, 0, 0 };
yxyang 4:095b126178df 508
yxyang 4:095b126178df 509 // reset device, reset all registers, clear gyro and accelerometer bias
yxyang 4:095b126178df 510 // registers
yxyang 4:095b126178df 511 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 512 0x80); // Write a one to bit 7 reset bit; toggle reset device
yxyang 4:095b126178df 513 wait (0.1);
yxyang 4:095b126178df 514
yxyang 4:095b126178df 515 // get stable time source
yxyang 4:095b126178df 516 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 =
yxyang 4:095b126178df 517 // 001
yxyang 4:095b126178df 518 writeByte (MPU6050_ADDRESS, PWR_MGMT_1, 0x01);
yxyang 4:095b126178df 519 writeByte (MPU6050_ADDRESS, PWR_MGMT_2, 0x00);
yxyang 4:095b126178df 520 wait (0.2);
yxyang 4:095b126178df 521
yxyang 4:095b126178df 522 // Configure device for bias calculation
yxyang 4:095b126178df 523 writeByte (MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts
yxyang 4:095b126178df 524 writeByte (MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO
yxyang 4:095b126178df 525 writeByte (MPU6050_ADDRESS, PWR_MGMT_1,
yxyang 4:095b126178df 526 0x00); // Turn on internal clock source
yxyang 4:095b126178df 527 writeByte (MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
yxyang 4:095b126178df 528 writeByte (MPU6050_ADDRESS, USER_CTRL,
yxyang 4:095b126178df 529 0x00); // Disable FIFO and I2C master modes
yxyang 4:095b126178df 530 writeByte (MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP
yxyang 4:095b126178df 531 wait (0.015);
yxyang 4:095b126178df 532
yxyang 4:095b126178df 533 // Configure MPU6050 gyro and accelerometer for bias calculation
yxyang 4:095b126178df 534 writeByte (MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz
yxyang 4:095b126178df 535 writeByte (MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz
yxyang 4:095b126178df 536 writeByte (MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to
yxyang 4:095b126178df 537 // 250 degrees per second,
yxyang 4:095b126178df 538 // maximum sensitivity
yxyang 4:095b126178df 539 writeByte (
yxyang 4:095b126178df 540 MPU6050_ADDRESS, ACCEL_CONFIG,
yxyang 4:095b126178df 541 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
yxyang 4:095b126178df 542
yxyang 4:095b126178df 543 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec
yxyang 4:095b126178df 544 uint16_t accelsensitivity = 16384; // = 16384 LSB/g
onehorse 1:cea9d83b8636 545
yxyang 4:095b126178df 546 // Configure FIFO to capture accelerometer and gyro data for bias
yxyang 4:095b126178df 547 // calculation
yxyang 4:095b126178df 548 writeByte (MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO
yxyang 4:095b126178df 549 writeByte (MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and
yxyang 4:095b126178df 550 // accelerometer sensors for
yxyang 4:095b126178df 551 // FIFO (max size 1024 bytes
yxyang 4:095b126178df 552 // in MPU-6050)
yxyang 4:095b126178df 553 wait (0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes
yxyang 4:095b126178df 554
yxyang 4:095b126178df 555 // At end of sample accumulation, turn off FIFO sensor read
yxyang 4:095b126178df 556 writeByte (MPU6050_ADDRESS, FIFO_EN,
yxyang 4:095b126178df 557 0x00); // Disable gyro and accelerometer sensors for FIFO
yxyang 4:095b126178df 558 readBytes (MPU6050_ADDRESS, FIFO_COUNTH, 2,
yxyang 4:095b126178df 559 &data[0]); // read FIFO sample count
yxyang 4:095b126178df 560 fifo_count = ((uint16_t)data[0] << 8) | data[1];
yxyang 4:095b126178df 561 packet_count = fifo_count / 12; // How many sets of full gyro and
yxyang 4:095b126178df 562 // accelerometer data for averaging
onehorse 1:cea9d83b8636 563
yxyang 4:095b126178df 564 for (ii = 0; ii < packet_count; ii++)
yxyang 4:095b126178df 565 {
yxyang 4:095b126178df 566 int16_t accel_temp[3] = { 0, 0, 0 }, gyro_temp[3] = { 0, 0, 0 };
yxyang 4:095b126178df 567 readBytes (MPU6050_ADDRESS, FIFO_R_W, 12,
yxyang 4:095b126178df 568 &data[0]); // read data for averaging
yxyang 4:095b126178df 569 accel_temp[0] = (int16_t) (
yxyang 4:095b126178df 570 ((int16_t)data[0] << 8)
yxyang 4:095b126178df 571 | data[1]); // Form signed 16-bit integer for each sample in FIFO
yxyang 4:095b126178df 572 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]);
yxyang 4:095b126178df 573 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]);
yxyang 4:095b126178df 574 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7]);
yxyang 4:095b126178df 575 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9]);
yxyang 4:095b126178df 576 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]);
onehorse 1:cea9d83b8636 577
yxyang 4:095b126178df 578 accel_bias[0] += (int32_t)accel_temp[0]; // Sum individual signed
yxyang 4:095b126178df 579 // 16-bit biases to get
yxyang 4:095b126178df 580 // accumulated signed 32-bit
yxyang 4:095b126178df 581 // biases
yxyang 4:095b126178df 582 accel_bias[1] += (int32_t)accel_temp[1];
yxyang 4:095b126178df 583 accel_bias[2] += (int32_t)accel_temp[2];
yxyang 4:095b126178df 584 gyro_bias[0] += (int32_t)gyro_temp[0];
yxyang 4:095b126178df 585 gyro_bias[1] += (int32_t)gyro_temp[1];
yxyang 4:095b126178df 586 gyro_bias[2] += (int32_t)gyro_temp[2];
yxyang 4:095b126178df 587 }
yxyang 4:095b126178df 588 accel_bias[0]
yxyang 4:095b126178df 589 /= (int32_t)packet_count; // Normalize sums to get average count biases
yxyang 4:095b126178df 590 accel_bias[1] /= (int32_t)packet_count;
yxyang 4:095b126178df 591 accel_bias[2] /= (int32_t)packet_count;
yxyang 4:095b126178df 592 gyro_bias[0] /= (int32_t)packet_count;
yxyang 4:095b126178df 593 gyro_bias[1] /= (int32_t)packet_count;
yxyang 4:095b126178df 594 gyro_bias[2] /= (int32_t)packet_count;
onehorse 1:cea9d83b8636 595
yxyang 4:095b126178df 596 if (accel_bias[2] > 0L)
yxyang 4:095b126178df 597 {
yxyang 4:095b126178df 598 accel_bias[2] -= (int32_t)accelsensitivity;
yxyang 4:095b126178df 599 } // Remove gravity from the z-axis accelerometer bias calculation
yxyang 4:095b126178df 600 else
yxyang 4:095b126178df 601 {
yxyang 4:095b126178df 602 accel_bias[2] += (int32_t)accelsensitivity;
yxyang 4:095b126178df 603 }
yxyang 4:095b126178df 604
yxyang 4:095b126178df 605 // Construct the gyro biases for push to the hardware gyro bias registers,
yxyang 4:095b126178df 606 // which are reset to zero upon device startup
yxyang 4:095b126178df 607 data[0] = (-gyro_bias[0] / 4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB
yxyang 4:095b126178df 608 // per deg/s to conform to
yxyang 4:095b126178df 609 // expected bias input format
yxyang 4:095b126178df 610 data[1] = (-gyro_bias[0] / 4) & 0xFF; // Biases are additive, so change
yxyang 4:095b126178df 611 // sign on calculated average gyro
yxyang 4:095b126178df 612 // biases
yxyang 4:095b126178df 613 data[2] = (-gyro_bias[1] / 4 >> 8) & 0xFF;
yxyang 4:095b126178df 614 data[3] = (-gyro_bias[1] / 4) & 0xFF;
yxyang 4:095b126178df 615 data[4] = (-gyro_bias[2] / 4 >> 8) & 0xFF;
yxyang 4:095b126178df 616 data[5] = (-gyro_bias[2] / 4) & 0xFF;
yxyang 4:095b126178df 617
yxyang 4:095b126178df 618 // Push gyro biases to hardware registers
yxyang 4:095b126178df 619 writeByte (MPU6050_ADDRESS, XG_OFFS_USRH, data[0]);
yxyang 4:095b126178df 620 writeByte (MPU6050_ADDRESS, XG_OFFS_USRL, data[1]);
yxyang 4:095b126178df 621 writeByte (MPU6050_ADDRESS, YG_OFFS_USRH, data[2]);
yxyang 4:095b126178df 622 writeByte (MPU6050_ADDRESS, YG_OFFS_USRL, data[3]);
yxyang 4:095b126178df 623 writeByte (MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]);
yxyang 4:095b126178df 624 writeByte (MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]);
yxyang 4:095b126178df 625
yxyang 4:095b126178df 626 dest1[0] = (float)gyro_bias[0]
yxyang 4:095b126178df 627 / (float)gyrosensitivity; // construct gyro bias in deg/s for
yxyang 4:095b126178df 628 // later manual subtraction
yxyang 4:095b126178df 629 dest1[1] = (float)gyro_bias[1] / (float)gyrosensitivity;
yxyang 4:095b126178df 630 dest1[2] = (float)gyro_bias[2] / (float)gyrosensitivity;
yxyang 4:095b126178df 631
yxyang 4:095b126178df 632 // Construct the accelerometer biases for push to the hardware
yxyang 4:095b126178df 633 // accelerometer bias registers. These registers contain
yxyang 4:095b126178df 634 // factory trim values which must be added to the calculated accelerometer
yxyang 4:095b126178df 635 // biases; on boot up these registers will hold
yxyang 4:095b126178df 636 // non-zero values. In addition, bit 0 of the lower byte must be preserved
yxyang 4:095b126178df 637 // since it is used for temperature
yxyang 4:095b126178df 638 // compensation calculations. Accelerometer bias registers expect bias
yxyang 4:095b126178df 639 // input as 2048 LSB per g, so that
yxyang 4:095b126178df 640 // the accelerometer biases calculated above must be divided by 8.
onehorse 1:cea9d83b8636 641
yxyang 4:095b126178df 642 int32_t accel_bias_reg[3]
yxyang 4:095b126178df 643 = { 0, 0, 0 }; // A place to hold the factory accelerometer trim biases
yxyang 4:095b126178df 644 readBytes (MPU6050_ADDRESS, XA_OFFSET_H, 2,
yxyang 4:095b126178df 645 &data[0]); // Read factory accelerometer trim values
yxyang 4:095b126178df 646 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
yxyang 4:095b126178df 647 readBytes (MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]);
yxyang 4:095b126178df 648 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
yxyang 4:095b126178df 649 readBytes (MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
yxyang 4:095b126178df 650 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
yxyang 4:095b126178df 651
yxyang 4:095b126178df 652 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of
yxyang 4:095b126178df 653 // lower byte of accelerometer bias registers
yxyang 4:095b126178df 654 uint8_t mask_bit[3] = {
yxyang 4:095b126178df 655 0, 0, 0
yxyang 4:095b126178df 656 }; // Define array to hold mask bit for each accelerometer bias axis
yxyang 4:095b126178df 657
yxyang 4:095b126178df 658 for (ii = 0; ii < 3; ii++)
yxyang 4:095b126178df 659 {
yxyang 4:095b126178df 660 if (accel_bias_reg[ii] & mask)
yxyang 4:095b126178df 661 mask_bit[ii] = 0x01; // If temperature compensation bit is set,
yxyang 4:095b126178df 662 // record that fact in mask_bit
yxyang 4:095b126178df 663 }
onehorse 1:cea9d83b8636 664
yxyang 4:095b126178df 665 // Construct total accelerometer bias, including calculated average
yxyang 4:095b126178df 666 // accelerometer bias from above
yxyang 4:095b126178df 667 accel_bias_reg[0] -= (accel_bias[0] / 8); // Subtract calculated averaged
yxyang 4:095b126178df 668 // accelerometer bias scaled to
yxyang 4:095b126178df 669 // 2048 LSB/g (16 g full scale)
yxyang 4:095b126178df 670 accel_bias_reg[1] -= (accel_bias[1] / 8);
yxyang 4:095b126178df 671 accel_bias_reg[2] -= (accel_bias[2] / 8);
yxyang 4:095b126178df 672
yxyang 4:095b126178df 673 data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
yxyang 4:095b126178df 674 data[1] = (accel_bias_reg[0]) & 0xFF;
yxyang 4:095b126178df 675 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit
yxyang 4:095b126178df 676 // when writing back to accelerometer bias
yxyang 4:095b126178df 677 // registers
yxyang 4:095b126178df 678 data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
yxyang 4:095b126178df 679 data[3] = (accel_bias_reg[1]) & 0xFF;
yxyang 4:095b126178df 680 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit
yxyang 4:095b126178df 681 // when writing back to accelerometer bias
yxyang 4:095b126178df 682 // registers
yxyang 4:095b126178df 683 data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
yxyang 4:095b126178df 684 data[5] = (accel_bias_reg[2]) & 0xFF;
yxyang 4:095b126178df 685 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit
yxyang 4:095b126178df 686 // when writing back to accelerometer bias
yxyang 4:095b126178df 687 // registers
yxyang 4:095b126178df 688
yxyang 4:095b126178df 689 // Push accelerometer biases to hardware registers
yxyang 4:095b126178df 690 // writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]);
yxyang 4:095b126178df 691 // writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]);
yxyang 4:095b126178df 692 // writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]);
yxyang 4:095b126178df 693 // writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]);
yxyang 4:095b126178df 694 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]);
yxyang 4:095b126178df 695 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]);
onehorse 1:cea9d83b8636 696
yxyang 4:095b126178df 697 // Output scaled accelerometer biases for manual subtraction in the main
yxyang 4:095b126178df 698 // program
yxyang 4:095b126178df 699 dest2[0] = (float)accel_bias[0] / (float)accelsensitivity;
yxyang 4:095b126178df 700 dest2[1] = (float)accel_bias[1] / (float)accelsensitivity;
yxyang 4:095b126178df 701 dest2[2] = (float)accel_bias[2] / (float)accelsensitivity;
yxyang 4:095b126178df 702 }
yxyang 4:095b126178df 703
yxyang 4:095b126178df 704 // Accelerometer and gyroscope self test; check calibration wrt factory
yxyang 4:095b126178df 705 // settings
yxyang 4:095b126178df 706 void MPU6050SelfTest (float *destination) // Should return percent deviation
yxyang 4:095b126178df 707 // from factory trim values, +/- 14
yxyang 4:095b126178df 708 // or less deviation is a pass
yxyang 4:095b126178df 709 {
yxyang 4:095b126178df 710 uint8_t rawData[4] = { 0, 0, 0, 0 };
yxyang 4:095b126178df 711 uint8_t selfTest[6];
yxyang 4:095b126178df 712 float factoryTrim[6];
onehorse 1:cea9d83b8636 713
yxyang 4:095b126178df 714 // Configure the accelerometer for self-test
yxyang 4:095b126178df 715 writeByte (MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all
yxyang 4:095b126178df 716 // three axes and set
yxyang 4:095b126178df 717 // accelerometer range to
yxyang 4:095b126178df 718 // +/- 8 g
yxyang 4:095b126178df 719 writeByte (MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all
yxyang 4:095b126178df 720 // three axes and set gyro
yxyang 4:095b126178df 721 // range to +/- 250
yxyang 4:095b126178df 722 // degrees/s
yxyang 4:095b126178df 723 wait (0.25); // Delay a while to let the device execute the self-test
yxyang 4:095b126178df 724 // rawData[0]
yxyang 4:095b126178df 725 // = readByte (MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test
yxyang 4:095b126178df 726 // results
yxyang 4:095b126178df 727 // rawData[1]
yxyang 4:095b126178df 728 // = readByte (MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test
yxyang 4:095b126178df 729 // results
yxyang 4:095b126178df 730 // rawData[2]
yxyang 4:095b126178df 731 // = readByte (MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test
yxyang 4:095b126178df 732 // results
yxyang 4:095b126178df 733 // rawData[3] = readByte (MPU6050_ADDRESS,
yxyang 4:095b126178df 734 // SELF_TEST_A);
yxyang 4:095b126178df 735 // Mixed-axis self-test results
yxyang 4:095b126178df 736 // Extract the acceleration test results first
yxyang 4:095b126178df 737 selfTest[0] = (rawData[0] >> 3)
yxyang 4:095b126178df 738 | (rawData[3] & 0x30)
yxyang 4:095b126178df 739 >> 4; // XA_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 740 selfTest[1] = (rawData[1] >> 3)
yxyang 4:095b126178df 741 | (rawData[3] & 0x0C)
yxyang 4:095b126178df 742 >> 4; // YA_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 743 selfTest[2] = (rawData[2] >> 3)
yxyang 4:095b126178df 744 | (rawData[3] & 0x03)
yxyang 4:095b126178df 745 >> 4; // ZA_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 746 // Extract the gyration test results first
yxyang 4:095b126178df 747 selfTest[3]
yxyang 4:095b126178df 748 = rawData[0] & 0x1F; // XG_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 749 selfTest[4]
yxyang 4:095b126178df 750 = rawData[1] & 0x1F; // YG_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 751 selfTest[5]
yxyang 4:095b126178df 752 = rawData[2] & 0x1F; // ZG_TEST result is a five-bit unsigned integer
yxyang 4:095b126178df 753 // Process results to allow final comparison with factory set values
yxyang 4:095b126178df 754 factoryTrim[0] = (4096.0f * 0.34f)
yxyang 4:095b126178df 755 * (pow ((0.92f / 0.34f),
yxyang 4:095b126178df 756 ((selfTest[0] - 1.0f)
yxyang 4:095b126178df 757 / 30.0f))); // FT[Xa] factory trim calculation
yxyang 4:095b126178df 758 factoryTrim[1] = (4096.0f * 0.34f)
yxyang 4:095b126178df 759 * (pow ((0.92f / 0.34f),
yxyang 4:095b126178df 760 ((selfTest[1] - 1.0f)
yxyang 4:095b126178df 761 / 30.0f))); // FT[Ya] factory trim calculation
yxyang 4:095b126178df 762 factoryTrim[2] = (4096.0f * 0.34f)
yxyang 4:095b126178df 763 * (pow ((0.92f / 0.34f),
yxyang 4:095b126178df 764 ((selfTest[2] - 1.0f)
yxyang 4:095b126178df 765 / 30.0f))); // FT[Za] factory trim calculation
yxyang 4:095b126178df 766 factoryTrim[3]
yxyang 4:095b126178df 767 = (25.0f * 131.0f)
yxyang 4:095b126178df 768 * (pow (1.046f,
yxyang 4:095b126178df 769 (selfTest[3] - 1.0f))); // FT[Xg] factory trim calculation
yxyang 4:095b126178df 770 factoryTrim[4]
yxyang 4:095b126178df 771 = (-25.0f * 131.0f)
yxyang 4:095b126178df 772 * (pow (1.046f,
yxyang 4:095b126178df 773 (selfTest[4] - 1.0f))); // FT[Yg] factory trim calculation
yxyang 4:095b126178df 774 factoryTrim[5]
yxyang 4:095b126178df 775 = (25.0f * 131.0f)
yxyang 4:095b126178df 776 * (pow (1.046f,
yxyang 4:095b126178df 777 (selfTest[5] - 1.0f))); // FT[Zg] factory trim calculation
yxyang 4:095b126178df 778
yxyang 4:095b126178df 779 // Output self-test results and factory trim calculation if desired
yxyang 4:095b126178df 780 // Serial.println(selfTest[0]); Serial.println(selfTest[1]);
yxyang 4:095b126178df 781 // Serial.println(selfTest[2]);
yxyang 4:095b126178df 782 // Serial.println(selfTest[3]); Serial.println(selfTest[4]);
yxyang 4:095b126178df 783 // Serial.println(selfTest[5]);
yxyang 4:095b126178df 784 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]);
yxyang 4:095b126178df 785 // Serial.println(factoryTrim[2]);
yxyang 4:095b126178df 786 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]);
yxyang 4:095b126178df 787 // Serial.println(factoryTrim[5]);
yxyang 4:095b126178df 788
yxyang 4:095b126178df 789 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim
yxyang 4:095b126178df 790 // of the Self-Test Response
yxyang 4:095b126178df 791 // To get to percent, must multiply by 100 and subtract result from 100
yxyang 4:095b126178df 792 for (int i = 0; i < 6; i++)
yxyang 4:095b126178df 793 {
yxyang 4:095b126178df 794 destination[i] = 100.0f
yxyang 4:095b126178df 795 + 100.0f * (selfTest[i] - factoryTrim[i])
yxyang 4:095b126178df 796 / factoryTrim[i]; // Report percent differences
yxyang 4:095b126178df 797 }
yxyang 4:095b126178df 798 }
onehorse 1:cea9d83b8636 799
yxyang 4:095b126178df 800 // Implementation of Sebastian Madgwick's "...efficient orientation filter
yxyang 4:095b126178df 801 // for... inertial/magnetic sensor arrays"
yxyang 4:095b126178df 802 // (see http://www.x-io.co.uk/category/open-source/ for examples and more
yxyang 4:095b126178df 803 // details)
yxyang 4:095b126178df 804 // which fuses acceleration and rotation rate to produce a quaternion-based
yxyang 4:095b126178df 805 // estimate of relative
yxyang 4:095b126178df 806 // device orientation -- which can be converted to yaw, pitch, and roll.
yxyang 4:095b126178df 807 // Useful for stabilizing quadcopters, etc.
yxyang 4:095b126178df 808 // The performance of the orientation filter is at least as good as
yxyang 4:095b126178df 809 // conventional Kalman-based filtering algorithms
yxyang 4:095b126178df 810 // but is much less computationally intensive---it can be performed on a 3.3
yxyang 4:095b126178df 811 // V Pro Mini operating at 8 MHz!
yxyang 4:095b126178df 812 void
yxyang 4:095b126178df 813 MadgwickQuaternionUpdate (float ax, float ay, float az, float gx, float gy,
yxyang 4:095b126178df 814 float gz)
yxyang 4:095b126178df 815 {
yxyang 4:095b126178df 816 float q1 = q[0], q2 = q[1], q3 = q[2],
yxyang 4:095b126178df 817 q4 = q[3]; // short name local variable for readability
yxyang 4:095b126178df 818 float norm; // vector norm
yxyang 4:095b126178df 819 float f1, f2, f3; // objective funcyion elements
yxyang 4:095b126178df 820 float J_11or24, J_12or23, J_13or22, J_14or21, J_32,
yxyang 4:095b126178df 821 J_33; // objective function Jacobian elements
yxyang 4:095b126178df 822 float qDot1, qDot2, qDot3, qDot4;
yxyang 4:095b126178df 823 float hatDot1, hatDot2, hatDot3, hatDot4;
yxyang 4:095b126178df 824 float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error
yxyang 4:095b126178df 825
yxyang 4:095b126178df 826 // Auxiliary variables to avoid repeated arithmetic
yxyang 4:095b126178df 827 float _halfq1 = 0.5f * q1;
yxyang 4:095b126178df 828 float _halfq2 = 0.5f * q2;
yxyang 4:095b126178df 829 float _halfq3 = 0.5f * q3;
yxyang 4:095b126178df 830 float _halfq4 = 0.5f * q4;
yxyang 4:095b126178df 831 float _2q1 = 2.0f * q1;
yxyang 4:095b126178df 832 float _2q2 = 2.0f * q2;
yxyang 4:095b126178df 833 float _2q3 = 2.0f * q3;
yxyang 4:095b126178df 834 float _2q4 = 2.0f * q4;
yxyang 4:095b126178df 835 // float _2q1q3 = 2.0f * q1 * q3;
yxyang 4:095b126178df 836 // float _2q3q4 = 2.0f * q3 * q4;
yxyang 4:095b126178df 837
yxyang 4:095b126178df 838 // Normalise accelerometer measurement
yxyang 4:095b126178df 839 norm = sqrt (ax * ax + ay * ay + az * az);
yxyang 4:095b126178df 840 if (norm == 0.0f)
yxyang 4:095b126178df 841 return; // handle NaN
yxyang 4:095b126178df 842 norm = 1.0f / norm;
yxyang 4:095b126178df 843 ax *= norm;
yxyang 4:095b126178df 844 ay *= norm;
yxyang 4:095b126178df 845 az *= norm;
onehorse 1:cea9d83b8636 846
yxyang 4:095b126178df 847 // Compute the objective function and Jacobian
yxyang 4:095b126178df 848 f1 = _2q2 * q4 - _2q1 * q3 - ax;
yxyang 4:095b126178df 849 f2 = _2q1 * q2 + _2q3 * q4 - ay;
yxyang 4:095b126178df 850 f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az;
yxyang 4:095b126178df 851 J_11or24 = _2q3;
yxyang 4:095b126178df 852 J_12or23 = _2q4;
yxyang 4:095b126178df 853 J_13or22 = _2q1;
yxyang 4:095b126178df 854 J_14or21 = _2q2;
yxyang 4:095b126178df 855 J_32 = 2.0f * J_14or21;
yxyang 4:095b126178df 856 J_33 = 2.0f * J_11or24;
yxyang 4:095b126178df 857
yxyang 4:095b126178df 858 // Compute the gradient (matrix multiplication)
yxyang 4:095b126178df 859 hatDot1 = J_14or21 * f2 - J_11or24 * f1;
yxyang 4:095b126178df 860 hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3;
yxyang 4:095b126178df 861 hatDot3 = J_12or23 * f2 - J_33 * f3 - J_13or22 * f1;
yxyang 4:095b126178df 862 hatDot4 = J_14or21 * f1 + J_11or24 * f2;
yxyang 4:095b126178df 863
yxyang 4:095b126178df 864 // Normalize the gradient
yxyang 4:095b126178df 865 norm = sqrt (hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3
yxyang 4:095b126178df 866 + hatDot4 * hatDot4);
yxyang 4:095b126178df 867 hatDot1 /= norm;
yxyang 4:095b126178df 868 hatDot2 /= norm;
yxyang 4:095b126178df 869 hatDot3 /= norm;
yxyang 4:095b126178df 870 hatDot4 /= norm;
yxyang 4:095b126178df 871
yxyang 4:095b126178df 872 // Compute estimated gyroscope biases
yxyang 4:095b126178df 873 gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3;
yxyang 4:095b126178df 874 gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2;
yxyang 4:095b126178df 875 gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1;
onehorse 1:cea9d83b8636 876
yxyang 4:095b126178df 877 // Compute and remove gyroscope biases
yxyang 4:095b126178df 878 gbiasx += gerrx * deltat * zeta;
yxyang 4:095b126178df 879 gbiasy += gerry * deltat * zeta;
yxyang 4:095b126178df 880 gbiasz += gerrz * deltat * zeta;
yxyang 4:095b126178df 881 // gx -= gbiasx;
yxyang 4:095b126178df 882 // gy -= gbiasy;
yxyang 4:095b126178df 883 // gz -= gbiasz;
yxyang 4:095b126178df 884
yxyang 4:095b126178df 885 // Compute the quaternion derivative
yxyang 4:095b126178df 886 qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz;
yxyang 4:095b126178df 887 qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy;
yxyang 4:095b126178df 888 qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx;
yxyang 4:095b126178df 889 qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx;
yxyang 4:095b126178df 890
yxyang 4:095b126178df 891 // Compute then integrate estimated quaternion derivative
yxyang 4:095b126178df 892 q1 += (qDot1 - (beta * hatDot1)) * deltat;
yxyang 4:095b126178df 893 q2 += (qDot2 - (beta * hatDot2)) * deltat;
yxyang 4:095b126178df 894 q3 += (qDot3 - (beta * hatDot3)) * deltat;
yxyang 4:095b126178df 895 q4 += (qDot4 - (beta * hatDot4)) * deltat;
yxyang 4:095b126178df 896
yxyang 4:095b126178df 897 // Normalize the quaternion
yxyang 4:095b126178df 898 norm
yxyang 4:095b126178df 899 = sqrt (q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion
yxyang 4:095b126178df 900 norm = 1.0f / norm;
yxyang 4:095b126178df 901 q[0] = q1 * norm;
yxyang 4:095b126178df 902 q[1] = q2 * norm;
yxyang 4:095b126178df 903 q[2] = q3 * norm;
yxyang 4:095b126178df 904 q[3] = q4 * norm;
yxyang 4:095b126178df 905 }
yxyang 4:095b126178df 906 };
onehorse 1:cea9d83b8636 907 #endif