Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
MPU6050.h
00001 #ifndef MPU6050_H 00002 #define MPU6050_H 00003 00004 #include "mbed.h" 00005 #include "math.h" 00006 00007 // Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device 00008 // Invensense Inc., www.invensense.com 00009 // See also MPU-6050 Register Map and Descriptions, Revision 4.0, RM-MPU-6050A-00, 9/12/2012 for registers not listed in 00010 // above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor 00011 // 00012 #define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD 00013 #define YGOFFS_TC 0x01 00014 #define ZGOFFS_TC 0x02 00015 #define X_FINE_GAIN 0x03 // [7:0] fine gain 00016 #define Y_FINE_GAIN 0x04 00017 #define Z_FINE_GAIN 0x05 00018 #define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer 00019 #define XA_OFFSET_L_TC 0x07 00020 #define YA_OFFSET_H 0x08 00021 #define YA_OFFSET_L_TC 0x09 00022 #define ZA_OFFSET_H 0x0A 00023 #define ZA_OFFSET_L_TC 0x0B 00024 #define SELF_TEST_X 0x0D 00025 #define SELF_TEST_Y 0x0E 00026 #define SELF_TEST_Z 0x0F 00027 #define SELF_TEST_A 0x10 00028 #define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope; supported in MPU-6050? 00029 #define XG_OFFS_USRL 0x14 00030 #define YG_OFFS_USRH 0x15 00031 #define YG_OFFS_USRL 0x16 00032 #define ZG_OFFS_USRH 0x17 00033 #define ZG_OFFS_USRL 0x18 00034 #define SMPLRT_DIV 0x19 00035 #define CONFIG 0x1A 00036 #define GYRO_CONFIG 0x1B 00037 #define ACCEL_CONFIG 0x1C 00038 #define FF_THR 0x1D // Free-fall 00039 #define FF_DUR 0x1E // Free-fall 00040 #define MOT_THR 0x1F // Motion detection threshold bits [7:0] 00041 #define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms 00042 #define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] 00043 #define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms 00044 #define FIFO_EN 0x23 00045 #define I2C_MST_CTRL 0x24 00046 #define I2C_SLV0_ADDR 0x25 00047 #define I2C_SLV0_REG 0x26 00048 #define I2C_SLV0_CTRL 0x27 00049 #define I2C_SLV1_ADDR 0x28 00050 #define I2C_SLV1_REG 0x29 00051 #define I2C_SLV1_CTRL 0x2A 00052 #define I2C_SLV2_ADDR 0x2B 00053 #define I2C_SLV2_REG 0x2C 00054 #define I2C_SLV2_CTRL 0x2D 00055 #define I2C_SLV3_ADDR 0x2E 00056 #define I2C_SLV3_REG 0x2F 00057 #define I2C_SLV3_CTRL 0x30 00058 #define I2C_SLV4_ADDR 0x31 00059 #define I2C_SLV4_REG 0x32 00060 #define I2C_SLV4_DO 0x33 00061 #define I2C_SLV4_CTRL 0x34 00062 #define I2C_SLV4_DI 0x35 00063 #define I2C_MST_STATUS 0x36 00064 #define INT_PIN_CFG 0x37 00065 #define INT_ENABLE 0x38 00066 #define DMP_INT_STATUS 0x39 // Check DMP interrupt 00067 #define INT_STATUS 0x3A 00068 #define ACCEL_XOUT_H 0x3B 00069 #define ACCEL_XOUT_L 0x3C 00070 #define ACCEL_YOUT_H 0x3D 00071 #define ACCEL_YOUT_L 0x3E 00072 #define ACCEL_ZOUT_H 0x3F 00073 #define ACCEL_ZOUT_L 0x40 00074 #define TEMP_OUT_H 0x41 00075 #define TEMP_OUT_L 0x42 00076 #define GYRO_XOUT_H 0x43 00077 #define GYRO_XOUT_L 0x44 00078 #define GYRO_YOUT_H 0x45 00079 #define GYRO_YOUT_L 0x46 00080 #define GYRO_ZOUT_H 0x47 00081 #define GYRO_ZOUT_L 0x48 00082 #define EXT_SENS_DATA_00 0x49 00083 #define EXT_SENS_DATA_01 0x4A 00084 #define EXT_SENS_DATA_02 0x4B 00085 #define EXT_SENS_DATA_03 0x4C 00086 #define EXT_SENS_DATA_04 0x4D 00087 #define EXT_SENS_DATA_05 0x4E 00088 #define EXT_SENS_DATA_06 0x4F 00089 #define EXT_SENS_DATA_07 0x50 00090 #define EXT_SENS_DATA_08 0x51 00091 #define EXT_SENS_DATA_09 0x52 00092 #define EXT_SENS_DATA_10 0x53 00093 #define EXT_SENS_DATA_11 0x54 00094 #define EXT_SENS_DATA_12 0x55 00095 #define EXT_SENS_DATA_13 0x56 00096 #define EXT_SENS_DATA_14 0x57 00097 #define EXT_SENS_DATA_15 0x58 00098 #define EXT_SENS_DATA_16 0x59 00099 #define EXT_SENS_DATA_17 0x5A 00100 #define EXT_SENS_DATA_18 0x5B 00101 #define EXT_SENS_DATA_19 0x5C 00102 #define EXT_SENS_DATA_20 0x5D 00103 #define EXT_SENS_DATA_21 0x5E 00104 #define EXT_SENS_DATA_22 0x5F 00105 #define EXT_SENS_DATA_23 0x60 00106 #define MOT_DETECT_STATUS 0x61 00107 #define I2C_SLV0_DO 0x63 00108 #define I2C_SLV1_DO 0x64 00109 #define I2C_SLV2_DO 0x65 00110 #define I2C_SLV3_DO 0x66 00111 #define I2C_MST_DELAY_CTRL 0x67 00112 #define SIGNAL_PATH_RESET 0x68 00113 #define MOT_DETECT_CTRL 0x69 00114 #define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP 00115 #define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode 00116 #define PWR_MGMT_2 0x6C 00117 #define DMP_BANK 0x6D // Activates a specific bank in the DMP 00118 #define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank 00119 #define DMP_REG 0x6F // Register in DMP from which to read or to which to write 00120 #define DMP_REG_1 0x70 00121 #define DMP_REG_2 0x71 00122 #define FIFO_COUNTH 0x72 00123 #define FIFO_COUNTL 0x73 00124 #define FIFO_R_W 0x74 00125 #define WHO_AM_I_MPU6050 0x75 // Should return 0x68 00126 00127 // Using the GY-521 breakout board, I set ADO to 0 by grounding through a 4k7 resistor 00128 // Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 00129 #define ADO 0 00130 #if ADO 00131 #define MPU6050_ADDRESS 0x69<<1 // Device address when ADO = 1 00132 #else 00133 #define MPU6050_ADDRESS 0x68<<1 // Device address when ADO = 0 00134 #endif 00135 Timer t; 00136 // Set initial input parameters 00137 enum Ascale { 00138 AFS_2G = 0, 00139 AFS_4G, 00140 AFS_8G, 00141 AFS_16G 00142 }; 00143 00144 enum Gscale { 00145 GFS_250DPS = 0, 00146 GFS_500DPS, 00147 GFS_1000DPS, 00148 GFS_2000DPS 00149 }; 00150 00151 // Specify sensor full scale 00152 int Gscale = GFS_250DPS; 00153 int Ascale = AFS_2G; 00154 00155 //Set up I2C, (SDA,SCL) 00156 I2C i2c(PB_7,PB_6); 00157 00158 //DigitalOut myled(LED1); 00159 00160 float aRes, gRes; // scale resolutions per LSB for the sensors 00161 00162 // Pin definitions 00163 int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins 00164 00165 int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output 00166 float ax, ay, az; // Stores the real accel value in g's 00167 int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output 00168 float gx, gy, gz; // Stores the real gyro value in degrees per seconds 00169 float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer 00170 int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius 00171 float temperature; 00172 float SelfTest[6]; 00173 00174 int delt_t = 0; // used to control display output rate 00175 int count1 = 0; // used to control display output rate 00176 00177 // parameters for 6 DoF sensor fusion calculations 00178 float PI = 3.14159265358979323846f; 00179 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 00180 float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta 00181 float GyroMeasDrift = PI * (1.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) 00182 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 00183 //float pitch, yaw, roll; 00184 float deltat = 0.0f; // integration interval for both filter schemes 00185 int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval 00186 float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion 00187 00188 class MPU6050 { 00189 00190 protected: 00191 00192 public: 00193 //=================================================================================================================== 00194 //====== Set of useful function to access acceleratio, gyroscope, and temperature data 00195 //=================================================================================================================== 00196 00197 MPU6050(PinName SDA,PinName SCL) 00198 { 00199 I2C i2c(SDA,SCL); 00200 } 00201 void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) 00202 { 00203 char data_write[2]; 00204 data_write[0] = subAddress; 00205 data_write[1] = data; 00206 i2c.write(address, data_write, 2, 0); 00207 } 00208 00209 char readByte(uint8_t address, uint8_t subAddress) 00210 { 00211 char data[1]; // `data` will store the register data 00212 char data_write[1]; 00213 data_write[0] = subAddress; 00214 i2c.write(address, data_write, 1, 1); // no stop 00215 i2c.read(address, data, 1, 0); 00216 return data[0]; 00217 } 00218 00219 void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) 00220 { 00221 char data[14]; 00222 char data_write[1]; 00223 data_write[0] = subAddress; 00224 i2c.write(address, data_write, 1, 1); // no stop 00225 i2c.read(address, data, count, 0); 00226 for(int ii = 0; ii < count; ii++) { 00227 dest[ii] = data[ii]; 00228 } 00229 } 00230 00231 00232 void getGres() { 00233 switch (Gscale) 00234 { 00235 // Possible gyro scales (and their register bit settings) are: 00236 // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). 00237 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00238 case GFS_250DPS: 00239 gRes = 250.0/32768.0; 00240 break; 00241 case GFS_500DPS: 00242 gRes = 500.0/32768.0; 00243 break; 00244 case GFS_1000DPS: 00245 gRes = 1000.0/32768.0; 00246 break; 00247 case GFS_2000DPS: 00248 gRes = 2000.0/32768.0; 00249 break; 00250 } 00251 } 00252 00253 void getAres() { 00254 switch (Ascale) 00255 { 00256 // Possible accelerometer scales (and their register bit settings) are: 00257 // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). 00258 // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: 00259 case AFS_2G: 00260 aRes = 2.0/32768.0; 00261 break; 00262 case AFS_4G: 00263 aRes = 4.0/32768.0; 00264 break; 00265 case AFS_8G: 00266 aRes = 8.0/32768.0; 00267 break; 00268 case AFS_16G: 00269 aRes = 16.0/32768.0; 00270 break; 00271 } 00272 } 00273 00274 00275 void readAccelData(int16_t * destination) 00276 { 00277 uint8_t rawData[6]; // x/y/z accel register data stored here 00278 readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array 00279 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00280 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00281 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00282 } 00283 00284 void readGyroData(int16_t * destination) 00285 { 00286 uint8_t rawData[6]; // x/y/z gyro register data stored here 00287 readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array 00288 destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value 00289 destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; 00290 destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 00291 } 00292 00293 int16_t readTempData() 00294 { 00295 uint8_t rawData[2]; // x/y/z gyro register data stored here 00296 readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array 00297 return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value 00298 } 00299 00300 00301 00302 // Configure the motion detection control for low power accelerometer mode 00303 void LowPowerAccelOnly() 00304 { 00305 00306 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly 00307 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration 00308 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 00309 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out 00310 // consideration for these threshold evaluations; otherwise, the flags would be set all the time! 00311 00312 uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00313 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6] 00314 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running 00315 00316 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00317 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5] 00318 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running 00319 00320 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00321 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00322 // 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 00323 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter 00324 00325 c = readByte(MPU6050_ADDRESS, CONFIG); 00326 writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0] 00327 writeByte(MPU6050_ADDRESS, CONFIG, c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate 00328 00329 c = readByte(MPU6050_ADDRESS, INT_ENABLE); 00330 writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts 00331 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40); // Enable motion threshold (bits 5) interrupt only 00332 00333 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold 00334 // for at least the counter duration 00335 writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg 00336 writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate 00337 00338 wait(0.1); // Add delay for accumulation of samples 00339 00340 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00341 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] 00342 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7; hold the initial accleration value as a referance 00343 00344 c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); 00345 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7] 00346 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2]) 00347 00348 c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); 00349 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5 00350 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts 00351 00352 } 00353 00354 00355 void resetMPU6050() { 00356 // reset device 00357 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00358 wait(0.1); 00359 } 00360 00361 00362 void initMPU6050() 00363 { 00364 // Initialize MPU6050 device 00365 // wake up device 00366 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 00367 wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt 00368 00369 // get stable time source 00370 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00371 00372 // Configure Gyro and Accelerometer 00373 // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 00374 // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both 00375 // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate 00376 writeByte(MPU6050_ADDRESS, CONFIG, 0x03); 00377 00378 // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) 00379 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above 00380 00381 // Set gyroscope full scale range 00382 // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 00383 uint8_t c = readByte(MPU6050_ADDRESS, GYRO_CONFIG); 00384 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00385 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00386 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro 00387 00388 // Set accelerometer configuration 00389 c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); 00390 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 00391 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] 00392 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 00393 00394 // Configure Interrupts and Bypass Enable 00395 // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 00396 // can join the I2C bus and all can be controlled by the Arduino as master 00397 writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22); 00398 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt 00399 } 00400 00401 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average 00402 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. 00403 void calibrateMPU6050(float * dest1, float * dest2) 00404 { 00405 uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data 00406 uint16_t ii, packet_count, fifo_count; 00407 int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; 00408 00409 // reset device, reset all registers, clear gyro and accelerometer bias registers 00410 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device 00411 wait(0.1); 00412 00413 // get stable time source 00414 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 00415 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); 00416 writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 00417 wait(0.2); 00418 00419 // Configure device for bias calculation 00420 writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts 00421 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO 00422 writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source 00423 writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master 00424 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes 00425 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP 00426 wait(0.015); 00427 00428 // Configure MPU6050 gyro and accelerometer for bias calculation 00429 writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz 00430 writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz 00431 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity 00432 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity 00433 00434 uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec 00435 uint16_t accelsensitivity = 16384; // = 16384 LSB/g 00436 00437 // Configure FIFO to capture accelerometer and gyro data for bias calculation 00438 writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO 00439 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050) 00440 wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes 00441 00442 // At end of sample accumulation, turn off FIFO sensor read 00443 writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO 00444 readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count 00445 fifo_count = ((uint16_t)data[0] << 8) | data[1]; 00446 packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging 00447 00448 for (ii = 0; ii < packet_count; ii++) { 00449 int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; 00450 readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging 00451 accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO 00452 accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; 00453 accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; 00454 gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; 00455 gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; 00456 gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; 00457 00458 accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases 00459 accel_bias[1] += (int32_t) accel_temp[1]; 00460 accel_bias[2] += (int32_t) accel_temp[2]; 00461 gyro_bias[0] += (int32_t) gyro_temp[0]; 00462 gyro_bias[1] += (int32_t) gyro_temp[1]; 00463 gyro_bias[2] += (int32_t) gyro_temp[2]; 00464 00465 } 00466 accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases 00467 accel_bias[1] /= (int32_t) packet_count; 00468 accel_bias[2] /= (int32_t) packet_count; 00469 gyro_bias[0] /= (int32_t) packet_count; 00470 gyro_bias[1] /= (int32_t) packet_count; 00471 gyro_bias[2] /= (int32_t) packet_count; 00472 00473 if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;} // Remove gravity from the z-axis accelerometer bias calculation 00474 else {accel_bias[2] += (int32_t) accelsensitivity;} 00475 00476 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup 00477 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 00478 data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases 00479 data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; 00480 data[3] = (-gyro_bias[1]/4) & 0xFF; 00481 data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; 00482 data[5] = (-gyro_bias[2]/4) & 0xFF; 00483 00484 // Push gyro biases to hardware registers 00485 writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 00486 writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); 00487 writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); 00488 writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); 00489 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); 00490 writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); 00491 00492 dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction 00493 dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; 00494 dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; 00495 00496 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain 00497 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold 00498 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature 00499 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that 00500 // the accelerometer biases calculated above must be divided by 8. 00501 00502 int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases 00503 readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values 00504 accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00505 readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]); 00506 accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00507 readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]); 00508 accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; 00509 00510 uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers 00511 uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis 00512 00513 for(ii = 0; ii < 3; ii++) { 00514 if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit 00515 } 00516 00517 // Construct total accelerometer bias, including calculated average accelerometer bias from above 00518 accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) 00519 accel_bias_reg[1] -= (accel_bias[1]/8); 00520 accel_bias_reg[2] -= (accel_bias[2]/8); 00521 00522 data[0] = (accel_bias_reg[0] >> 8) & 0xFF; 00523 data[1] = (accel_bias_reg[0]) & 0xFF; 00524 data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00525 data[2] = (accel_bias_reg[1] >> 8) & 0xFF; 00526 data[3] = (accel_bias_reg[1]) & 0xFF; 00527 data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00528 data[4] = (accel_bias_reg[2] >> 8) & 0xFF; 00529 data[5] = (accel_bias_reg[2]) & 0xFF; 00530 data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers 00531 00532 // Push accelerometer biases to hardware registers 00533 // writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]); 00534 // writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]); 00535 // writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]); 00536 // writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]); 00537 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]); 00538 // writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]); 00539 00540 // Output scaled accelerometer biases for manual subtraction in the main program 00541 dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 00542 dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; 00543 dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; 00544 } 00545 00546 00547 // Accelerometer and gyroscope self test; check calibration wrt factory settings 00548 void MPU6050SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass 00549 { 00550 uint8_t rawData[4] = {0, 0, 0, 0}; 00551 uint8_t selfTest[6]; 00552 float factoryTrim[6]; 00553 00554 // Configure the accelerometer for self-test 00555 writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g 00556 writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s 00557 wait(0.25); // Delay a while to let the device execute the self-test 00558 rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results 00559 rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results 00560 rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results 00561 rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results 00562 // Extract the acceleration test results first 00563 selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer 00564 selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer 00565 selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer 00566 // Extract the gyration test results first 00567 selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer 00568 selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer 00569 selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer 00570 // Process results to allow final comparison with factory set values 00571 factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation 00572 factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation 00573 factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation 00574 factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation 00575 factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation 00576 factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation 00577 00578 // Output self-test results and factory trim calculation if desired 00579 // Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); 00580 // Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); 00581 // Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); 00582 // Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); 00583 00584 // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response 00585 // To get to percent, must multiply by 100 and subtract result from 100 00586 for (int i = 0; i < 6; i++) { 00587 destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences 00588 } 00589 00590 } 00591 00592 00593 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" 00594 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details) 00595 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative 00596 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. 00597 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms 00598 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! 00599 void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz) 00600 { 00601 float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability 00602 float norm; // vector norm 00603 float f1, f2, f3; // objective funcyion elements 00604 float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements 00605 float qDot1, qDot2, qDot3, qDot4; 00606 float hatDot1, hatDot2, hatDot3, hatDot4; 00607 float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error 00608 00609 // Auxiliary variables to avoid repeated arithmetic 00610 float _halfq1 = 0.5f * q1; 00611 float _halfq2 = 0.5f * q2; 00612 float _halfq3 = 0.5f * q3; 00613 float _halfq4 = 0.5f * q4; 00614 float _2q1 = 2.0f * q1; 00615 float _2q2 = 2.0f * q2; 00616 float _2q3 = 2.0f * q3; 00617 float _2q4 = 2.0f * q4; 00618 // float _2q1q3 = 2.0f * q1 * q3; 00619 // float _2q3q4 = 2.0f * q3 * q4; 00620 00621 // Normalise accelerometer measurement 00622 norm = sqrt(ax * ax + ay * ay + az * az); 00623 if (norm == 0.0f) return; // handle NaN 00624 norm = 1.0f/norm; 00625 ax *= norm; 00626 ay *= norm; 00627 az *= norm; 00628 00629 // Compute the objective function and Jacobian 00630 f1 = _2q2 * q4 - _2q1 * q3 - ax; 00631 f2 = _2q1 * q2 + _2q3 * q4 - ay; 00632 f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az; 00633 J_11or24 = _2q3; 00634 J_12or23 = _2q4; 00635 J_13or22 = _2q1; 00636 J_14or21 = _2q2; 00637 J_32 = 2.0f * J_14or21; 00638 J_33 = 2.0f * J_11or24; 00639 00640 // Compute the gradient (matrix multiplication) 00641 hatDot1 = J_14or21 * f2 - J_11or24 * f1; 00642 hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3; 00643 hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1; 00644 hatDot4 = J_14or21 * f1 + J_11or24 * f2; 00645 00646 // Normalize the gradient 00647 norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4); 00648 hatDot1 /= norm; 00649 hatDot2 /= norm; 00650 hatDot3 /= norm; 00651 hatDot4 /= norm; 00652 00653 // Compute estimated gyroscope biases 00654 gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3; 00655 gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2; 00656 gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1; 00657 00658 // Compute and remove gyroscope biases 00659 gbiasx += gerrx * deltat * zeta; 00660 gbiasy += gerry * deltat * zeta; 00661 gbiasz += gerrz * deltat * zeta; 00662 // gx -= gbiasx; 00663 // gy -= gbiasy; 00664 // gz -= gbiasz; 00665 00666 // Compute the quaternion derivative 00667 qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz; 00668 qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy; 00669 qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx; 00670 qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx; 00671 00672 // Compute then integrate estimated quaternion derivative 00673 q1 += (qDot1 -(beta * hatDot1)) * deltat; 00674 q2 += (qDot2 -(beta * hatDot2)) * deltat; 00675 q3 += (qDot3 -(beta * hatDot3)) * deltat; 00676 q4 += (qDot4 -(beta * hatDot4)) * deltat; 00677 00678 // Normalize the quaternion 00679 norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion 00680 norm = 1.0f/norm; 00681 q[0] = q1 * norm; 00682 q[1] = q2 * norm; 00683 q[2] = q3 * norm; 00684 q[3] = q4 * norm; 00685 00686 } 00687 int Init() 00688 { 00689 i2c.frequency(400000); // use fast (400 kHz) I2C 00690 00691 t.start(); 00692 00693 00694 // Read the WHO_AM_I register, this is a good test of communication 00695 uint8_t whoami = readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Read WHO_AM_I register for MPU-6050 00696 //pc.printf("I AM 0x%x\n\r", whoami); pc.printf("I SHOULD BE 0x68\n\r"); 00697 00698 if (whoami == 0x68) // WHO_AM_I should always be 0x68 00699 { 00700 //pc.printf("MPU6050 is online..."); 00701 wait(1); 00702 00703 00704 MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values 00705 //pc.printf("x-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[0]); pc.printf("% of factory value \n\r"); 00706 // pc.printf("y-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[1]); pc.printf("% of factory value \n\r"); 00707 // pc.printf("z-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[2]); pc.printf("% of factory value \n\r"); 00708 // pc.printf("x-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[3]); pc.printf("% of factory value \n\r"); 00709 // pc.printf("y-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[4]); pc.printf("% of factory value \n\r"); 00710 // pc.printf("z-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[5]); pc.printf("% of factory value \n\r"); 00711 wait(1); 00712 00713 if(SelfTest[0] < 1.0f && SelfTest[1] < 1.0f && SelfTest[2] < 1.0f && SelfTest[3] < 1.0f && SelfTest[4] < 1.0f && SelfTest[5] < 1.0f) 00714 { 00715 resetMPU6050(); // Reset registers to default in preparation for device calibration 00716 calibrateMPU6050(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers 00717 initMPU6050(); //pc.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature 00718 wait(2); 00719 } 00720 else 00721 { 00722 //pc.printf("Device did not the pass self-test!\n\r"); 00723 return 1; 00724 } 00725 } 00726 else 00727 { 00728 // pc.printf("Could not connect to MPU6050: \n\r"); 00729 // pc.printf("%#x \n", whoami); 00730 return 1; 00731 // while(1) ; // Loop forever if communication doesn't happen 00732 } 00733 return 0; 00734 } 00735 void receiveData(float *yaw, float *pitch , float *roll ) 00736 { 00737 if(readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { // check if data ready interrupt 00738 readAccelData(accelCount); // Read the x/y/z adc values 00739 getAres(); 00740 00741 // Now we'll calculate the accleration value into actual g's 00742 ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set 00743 ay = (float)accelCount[1]*aRes - accelBias[1]; 00744 az = (float)accelCount[2]*aRes - accelBias[2]; 00745 00746 readGyroData(gyroCount); // Read the x/y/z adc values 00747 getGres(); 00748 00749 // Calculate the gyro value into actual degrees per second 00750 gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set 00751 gy = (float)gyroCount[1]*gRes; // - gyroBias[1]; 00752 gz = (float)gyroCount[2]*gRes; // - gyroBias[2]; 00753 00754 tempCount = readTempData(); // Read the x/y/z adc values 00755 temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade 00756 } 00757 00758 Now = t.read_us(); 00759 deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update 00760 lastUpdate = Now; 00761 00762 // sum += deltat; 00763 // sumCount++; 00764 00765 if(lastUpdate - firstUpdate > 10000000.0f) { 00766 beta = 0.04; // decrease filter gain after stabilized 00767 zeta = 0.015; // increasey bias drift gain after stabilized 00768 } 00769 00770 // Pass gyro rate as rad/s 00771 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f); 00772 00773 // Serial print and/or display at 0.5 s rate independent of data rates 00774 delt_t = t.read_ms() - count1; 00775 if (delt_t > 500) { // update LCD once per half-second independent of read rate 00776 00777 // pc.printf("ax = %f", 1000*ax); 00778 // pc.printf(" ay = %f", 1000*ay); 00779 // pc.printf(" az = %f mg\n\r", 1000*az); 00780 // 00781 // pc.printf("gx = %f", gx); 00782 // pc.printf(" gy = %f", gy); 00783 // pc.printf(" gz = %f deg/s\n\r", gz); 00784 // 00785 // pc.printf(" temperature = %f C\n\r", temperature); 00786 // 00787 // pc.printf("q0 = %f\n\r", q[0]); 00788 // pc.printf("q1 = %f\n\r", q[1]); 00789 // pc.printf("q2 = %f\n\r", q[2]); 00790 // pc.printf("q3 = %f\n\r", q[3]); 00791 00792 *yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); 00793 *pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); 00794 *roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); 00795 *pitch *= 180.0f / PI; 00796 *yaw *= 180.0f / PI; 00797 *roll *= 180.0f / PI; 00798 00799 //pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll); 00800 00801 count1 = t.read_ms(); 00802 } 00803 } 00804 00805 00806 }; 00807 00808 #endif
Generated on Tue Jul 12 2022 18:19:54 by
1.7.2