Nothing was changed

Dependents:   sensor_library_test sensor_library_test

Committer:
aolgu003
Date:
Mon Jul 25 00:19:42 2016 +0000
Revision:
0:156893f75ab0
Moved MPU6050 to a library folder

Who changed what in which revision?

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