操舵ソースコードの第一稿です。 メイン基盤用のソースコードです。

Dependencies:   ADXL345_I2C INA226 mbed SDFileSystem

Committer:
YusukeWakuta
Date:
Wed Jan 20 13:33:43 2016 +0000
Revision:
1:247ccea89495
Parent:
0:77917230ce6d
1?20?????

Who changed what in which revision?

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