MPU6050 library file for FRDMk64

Committer:
sdloh
Date:
Tue Apr 12 21:16:28 2016 +0000
Revision:
0:b8c24882a891
MPU6050 with FRDMk64

Who changed what in which revision?

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