加速度センサのライブラリです。

Dependents:   MPU6050_get_offset MPU6050_cansat MPU6050_cansat test2 ... more

Committer:
falconsyunya
Date:
Sat Nov 24 00:00:54 2018 +0000
Revision:
2:51bd76211e3b
Parent:
1:118c17d86087
2018/11/24 9:00

Who changed what in which revision?

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