Wireless auto note device

Dependencies:   BLE_API invisdrum X_NUCLEO_IDB0XA1 kalman mbed

Committer:
fxanhkhoa
Date:
Tue Nov 22 02:57:33 2016 +0000
Revision:
0:ffd0caf3db9f
WAND PROJECT

Who changed what in which revision?

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