liang brain / Mbed 2 deprecated EX_encoder_PID_QianYuyang

Dependencies:   mbed QEI-1 nRF24L01P xiugai

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MPU6050.h Source File

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 
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     I2C i2c;
00192     Timer t;
00193  
00194     public:
00195   //===================================================================================================================
00196 //====== Set of useful function to access acceleratio, gyroscope, and temperature data
00197 //===================================================================================================================
00198 
00199     mpu6050(PinName SDA,PinName SCL):i2c(SDA,SCL)
00200 {
00201     t.start();
00202     i2c.frequency(400000);
00203 }
00204     void writeByte(uint8_t address, uint8_t subAddress, uint8_t data)
00205 {
00206    char data_write[2];
00207    data_write[0] = subAddress;
00208    data_write[1] = data;
00209    i2c.write(address, data_write, 2, 0);
00210 }
00211 
00212     char readByte(uint8_t address, uint8_t subAddress)
00213 {
00214     char data[1]; // `data` will store the register data     
00215     char data_write[1];
00216     data_write[0] = subAddress;
00217     i2c.write(address, data_write, 1, 1); // no stop
00218     i2c.read(address, data, 1, 0); 
00219     return data[0]; 
00220 }
00221 
00222     void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest)
00223 {     
00224     char data[14];
00225     char data_write[1];
00226     data_write[0] = subAddress;
00227     i2c.write(address, data_write, 1, 1); // no stop
00228     i2c.read(address, data, count, 0); 
00229     for(int ii = 0; ii < count; ii++) {
00230      dest[ii] = data[ii];
00231     }
00232 } 
00233  
00234 
00235 void getGres() {
00236   switch (Gscale)
00237   {
00238     // Possible gyro scales (and their register bit settings) are:
00239     // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS  (11). 
00240         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00241     case GFS_250DPS:
00242           gRes = 250.0/32768.0;
00243           break;
00244     case GFS_500DPS:
00245           gRes = 500.0/32768.0;
00246           break;
00247     case GFS_1000DPS:
00248           gRes = 1000.0/32768.0;
00249           break;
00250     case GFS_2000DPS:
00251           gRes = 2000.0/32768.0;
00252           break;
00253   }
00254 }
00255 
00256 void getAres() {
00257   switch (Ascale)
00258   {
00259     // Possible accelerometer scales (and their register bit settings) are:
00260     // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs  (11). 
00261         // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value:
00262     case AFS_2G:
00263           aRes = 2.0/32768.0;
00264           break;
00265     case AFS_4G:
00266           aRes = 4.0/32768.0;
00267           break;
00268     case AFS_8G:
00269           aRes = 8.0/32768.0;
00270           break;
00271     case AFS_16G:
00272           aRes = 16.0/32768.0;
00273           break;
00274   }
00275 }
00276 
00277 
00278 void readAccelData(int16_t * destination)
00279 {
00280   uint8_t rawData[6];  // x/y/z accel register data stored here
00281   readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers into data array
00282   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00283   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00284   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00285 }
00286 
00287 void readGyroData(int16_t * destination)
00288 {
00289   uint8_t rawData[6];  // x/y/z gyro register data stored here
00290   readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]);  // Read the six raw data registers sequentially into data array
00291   destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ;  // Turn the MSB and LSB into a signed 16-bit value
00292   destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ;  
00293   destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; 
00294 }
00295 
00296 int16_t readTempData()
00297 {
00298   uint8_t rawData[2];  // x/y/z gyro register data stored here
00299   readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]);  // Read the two raw data registers sequentially into data array 
00300   return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ;  // Turn the MSB and LSB into a 16-bit value
00301 }
00302 
00303 
00304 
00305 // Configure the motion detection control for low power accelerometer mode
00306 void LowPowerAccelOnly()
00307 {
00308 
00309 // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly
00310 // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration
00311 // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a 
00312 // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out
00313 // consideration for these threshold evaluations; otherwise, the flags would be set all the time!
00314   
00315   uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1);
00316   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6]
00317   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c |  0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running
00318 
00319   c = readByte(MPU6050_ADDRESS, PWR_MGMT_2);
00320   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5]
00321   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c |  0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running
00322     
00323   c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00324   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0]
00325 // 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
00326   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG,  c | 0x00);  // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter
00327 
00328   c = readByte(MPU6050_ADDRESS, CONFIG);
00329   writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0]
00330   writeByte(MPU6050_ADDRESS, CONFIG, c |  0x00);  // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate
00331     
00332   c = readByte(MPU6050_ADDRESS, INT_ENABLE);
00333   writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF);  // Clear all interrupts
00334   writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40);  // Enable motion threshold (bits 5) interrupt only
00335   
00336 // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold
00337 // for at least the counter duration
00338   writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg
00339   writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1  ms; LSB is 1 ms @ 1 kHz rate
00340   
00341   wait(0.1);  // Add delay for accumulation of samples
00342   
00343   c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00344   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0]
00345   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c |  0x07);  // Set ACCEL_HPF to 7; hold the initial accleration value as a referance
00346    
00347   c = readByte(MPU6050_ADDRESS, PWR_MGMT_2);
00348   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7]
00349   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c |  0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2])  
00350 
00351   c = readByte(MPU6050_ADDRESS, PWR_MGMT_1);
00352   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5
00353   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c |  0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts
00354 
00355 }
00356 
00357 
00358 void resetMPU6050() {
00359   // reset device
00360   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00361   wait(0.1);
00362   }
00363   
00364   
00365 void initMPU6050()
00366 {  
00367  // Initialize MPU6050 device
00368  // wake up device
00369   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors 
00370   wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt  
00371 
00372  // get stable time source
00373   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);  // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00374 
00375  // Configure Gyro and Accelerometer
00376  // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; 
00377  // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both
00378  // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate
00379   writeByte(MPU6050_ADDRESS, CONFIG, 0x03);  
00380  
00381  // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV)
00382   writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04);  // Use a 200 Hz rate; the same rate set in CONFIG above
00383  
00384  // Set gyroscope full scale range
00385  // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3
00386   uint8_t c =  readByte(MPU6050_ADDRESS, GYRO_CONFIG);
00387   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00388   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00389   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro
00390    
00391  // Set accelerometer configuration
00392   c =  readByte(MPU6050_ADDRESS, ACCEL_CONFIG);
00393   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] 
00394   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3]
00395   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer 
00396 
00397   // Configure Interrupts and Bypass Enable
00398   // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips 
00399   // can join the I2C bus and all can be controlled by the Arduino as master
00400    writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22);    
00401    writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01);  // Enable data ready (bit 0) interrupt
00402 }
00403 
00404 // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average
00405 // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
00406 void calibrateMPU6050(float * dest1, float * dest2)
00407 {  
00408   uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data
00409   uint16_t ii, packet_count, fifo_count;
00410   int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0};
00411   
00412 // reset device, reset all registers, clear gyro and accelerometer bias registers
00413   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device
00414   wait(0.1);  
00415    
00416 // get stable time source
00417 // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001
00418   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01);  
00419   writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); 
00420   wait(0.2);
00421   
00422 // Configure device for bias calculation
00423   writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00);   // Disable all interrupts
00424   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00);      // Disable FIFO
00425   writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00);   // Turn on internal clock source
00426   writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master
00427   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00);    // Disable FIFO and I2C master modes
00428   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C);    // Reset FIFO and DMP
00429   wait(0.015);
00430   
00431 // Configure MPU6050 gyro and accelerometer for bias calculation
00432   writeByte(MPU6050_ADDRESS, CONFIG, 0x01);      // Set low-pass filter to 188 Hz
00433   writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00);  // Set sample rate to 1 kHz
00434   writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00);  // Set gyro full-scale to 250 degrees per second, maximum sensitivity
00435   writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity
00436  
00437   uint16_t  gyrosensitivity  = 131;   // = 131 LSB/degrees/sec
00438   uint16_t  accelsensitivity = 16384;  // = 16384 LSB/g
00439 
00440 // Configure FIFO to capture accelerometer and gyro data for bias calculation
00441   writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40);   // Enable FIFO  
00442   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78);     // Enable gyro and accelerometer sensors for FIFO  (max size 1024 bytes in MPU-6050)
00443   wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes
00444 
00445 // At end of sample accumulation, turn off FIFO sensor read
00446   writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00);        // Disable gyro and accelerometer sensors for FIFO
00447   readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count
00448   fifo_count = ((uint16_t)data[0] << 8) | data[1];
00449   packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging
00450 
00451   for (ii = 0; ii < packet_count; ii++) {
00452     int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0};
00453     readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging
00454     accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1]  ) ;  // Form signed 16-bit integer for each sample in FIFO
00455     accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3]  ) ;
00456     accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5]  ) ;    
00457     gyro_temp[0]  = (int16_t) (((int16_t)data[6] << 8) | data[7]  ) ;
00458     gyro_temp[1]  = (int16_t) (((int16_t)data[8] << 8) | data[9]  ) ;
00459     gyro_temp[2]  = (int16_t) (((int16_t)data[10] << 8) | data[11]) ;
00460     
00461     accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases
00462     accel_bias[1] += (int32_t) accel_temp[1];
00463     accel_bias[2] += (int32_t) accel_temp[2];
00464     gyro_bias[0]  += (int32_t) gyro_temp[0];
00465     gyro_bias[1]  += (int32_t) gyro_temp[1];
00466     gyro_bias[2]  += (int32_t) gyro_temp[2];
00467             
00468 }
00469     accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases
00470     accel_bias[1] /= (int32_t) packet_count;
00471     accel_bias[2] /= (int32_t) packet_count;
00472     gyro_bias[0]  /= (int32_t) packet_count;
00473     gyro_bias[1]  /= (int32_t) packet_count;
00474     gyro_bias[2]  /= (int32_t) packet_count;
00475     
00476   if(accel_bias[2] > 0L) {accel_bias[2] -= (int32_t) accelsensitivity;}  // Remove gravity from the z-axis accelerometer bias calculation
00477   else {accel_bias[2] += (int32_t) accelsensitivity;}
00478  
00479 // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup
00480   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
00481   data[1] = (-gyro_bias[0]/4)       & 0xFF; // Biases are additive, so change sign on calculated average gyro biases
00482   data[2] = (-gyro_bias[1]/4  >> 8) & 0xFF;
00483   data[3] = (-gyro_bias[1]/4)       & 0xFF;
00484   data[4] = (-gyro_bias[2]/4  >> 8) & 0xFF;
00485   data[5] = (-gyro_bias[2]/4)       & 0xFF;
00486 
00487 // Push gyro biases to hardware registers
00488   writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); 
00489   writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]);
00490   writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]);
00491   writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]);
00492   writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]);
00493   writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]);
00494 
00495   dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction
00496   dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity;
00497   dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity;
00498 
00499 // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain
00500 // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold
00501 // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature
00502 // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that
00503 // the accelerometer biases calculated above must be divided by 8.
00504 
00505   int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases
00506   readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values
00507   accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00508   readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]);
00509   accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00510   readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]);
00511   accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1];
00512   
00513   uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers
00514   uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis
00515   
00516   for(ii = 0; ii < 3; ii++) {
00517     if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit
00518   }
00519 
00520   // Construct total accelerometer bias, including calculated average accelerometer bias from above
00521   accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale)
00522   accel_bias_reg[1] -= (accel_bias[1]/8);
00523   accel_bias_reg[2] -= (accel_bias[2]/8);
00524  
00525   data[0] = (accel_bias_reg[0] >> 8) & 0xFF;
00526   data[1] = (accel_bias_reg[0])      & 0xFF;
00527   data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00528   data[2] = (accel_bias_reg[1] >> 8) & 0xFF;
00529   data[3] = (accel_bias_reg[1])      & 0xFF;
00530   data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00531   data[4] = (accel_bias_reg[2] >> 8) & 0xFF;
00532   data[5] = (accel_bias_reg[2])      & 0xFF;
00533   data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers
00534 
00535   // Push accelerometer biases to hardware registers
00536 //  writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]);  
00537 //  writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]);
00538 //  writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]);
00539 //  writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]);  
00540 //  writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]);
00541 //  writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]);
00542 
00543 // Output scaled accelerometer biases for manual subtraction in the main program
00544    dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; 
00545    dest2[1] = (float)accel_bias[1]/(float)accelsensitivity;
00546    dest2[2] = (float)accel_bias[2]/(float)accelsensitivity;
00547 }
00548 
00549 
00550 // Accelerometer and gyroscope self test; check calibration wrt factory settings
00551 void MPU6050SelfTest(float * destination) // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass
00552 {
00553    uint8_t rawData[4] = {0, 0, 0, 0};
00554    uint8_t selfTest[6];
00555    float factoryTrim[6];
00556    
00557    // Configure the accelerometer for self-test
00558    writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g
00559    writeByte(MPU6050_ADDRESS, GYRO_CONFIG,  0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s
00560    wait(0.25);  // Delay a while to let the device execute the self-test
00561    rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results
00562    rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results
00563    rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results
00564    rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results
00565    // Extract the acceleration test results first
00566    selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer
00567    selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer
00568    selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer
00569    // Extract the gyration test results first
00570    selfTest[3] = rawData[0]  & 0x1F ; // XG_TEST result is a five-bit unsigned integer
00571    selfTest[4] = rawData[1]  & 0x1F ; // YG_TEST result is a five-bit unsigned integer
00572    selfTest[5] = rawData[2]  & 0x1F ; // ZG_TEST result is a five-bit unsigned integer   
00573    // Process results to allow final comparison with factory set values
00574    factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation
00575    factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation
00576    factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation
00577    factoryTrim[3] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) ));             // FT[Xg] factory trim calculation
00578    factoryTrim[4] =  (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) ));             // FT[Yg] factory trim calculation
00579    factoryTrim[5] =  ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) ));             // FT[Zg] factory trim calculation
00580    
00581  //  Output self-test results and factory trim calculation if desired
00582  //  Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]);
00583  //  Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]);
00584  //  Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]);
00585  //  Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]);
00586 
00587  // Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response
00588  // To get to percent, must multiply by 100 and subtract result from 100
00589    for (int i = 0; i < 6; i++) {
00590      destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences
00591    }
00592    
00593 }
00594 
00595 
00596 // Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays"
00597 // (see http://www.x-io.co.uk/category/open-source/ for examples and more details)
00598 // which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative
00599 // device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc.
00600 // The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms
00601 // but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
00602         void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz)
00603         {
00604             float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3];         // short name local variable for readability
00605             float norm;                                               // vector norm
00606             float f1, f2, f3;                                         // objective funcyion elements
00607             float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements
00608             float qDot1, qDot2, qDot3, qDot4;
00609             float hatDot1, hatDot2, hatDot3, hatDot4;
00610             float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz;  // gyro bias error
00611 
00612             // Auxiliary variables to avoid repeated arithmetic
00613             float _halfq1 = 0.5f * q1;
00614             float _halfq2 = 0.5f * q2;
00615             float _halfq3 = 0.5f * q3;
00616             float _halfq4 = 0.5f * q4;
00617             float _2q1 = 2.0f * q1;
00618             float _2q2 = 2.0f * q2;
00619             float _2q3 = 2.0f * q3;
00620             float _2q4 = 2.0f * q4;
00621 //            float _2q1q3 = 2.0f * q1 * q3;
00622 //            float _2q3q4 = 2.0f * q3 * q4;
00623 
00624             // Normalise accelerometer measurement
00625             norm = sqrt(ax * ax + ay * ay + az * az);
00626             if (norm == 0.0f) return; // handle NaN
00627             norm = 1.0f/norm;
00628             ax *= norm;
00629             ay *= norm;
00630             az *= norm;
00631             
00632             // Compute the objective function and Jacobian
00633             f1 = _2q2 * q4 - _2q1 * q3 - ax;
00634             f2 = _2q1 * q2 + _2q3 * q4 - ay;
00635             f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az;
00636             J_11or24 = _2q3;
00637             J_12or23 = _2q4;
00638             J_13or22 = _2q1;
00639             J_14or21 = _2q2;
00640             J_32 = 2.0f * J_14or21;
00641             J_33 = 2.0f * J_11or24;
00642           
00643             // Compute the gradient (matrix multiplication)
00644             hatDot1 = J_14or21 * f2 - J_11or24 * f1;
00645             hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3;
00646             hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1;
00647             hatDot4 = J_14or21 * f1 + J_11or24 * f2;
00648             
00649             // Normalize the gradient
00650             norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4);
00651             hatDot1 /= norm;
00652             hatDot2 /= norm;
00653             hatDot3 /= norm;
00654             hatDot4 /= norm;
00655             
00656             // Compute estimated gyroscope biases
00657             gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3;
00658             gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2;
00659             gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1;
00660             
00661             // Compute and remove gyroscope biases
00662             gbiasx += gerrx * deltat * zeta;
00663             gbiasy += gerry * deltat * zeta;
00664             gbiasz += gerrz * deltat * zeta;
00665  //           gx -= gbiasx;
00666  //           gy -= gbiasy;
00667  //           gz -= gbiasz;
00668             
00669             // Compute the quaternion derivative
00670             qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz;
00671             qDot2 =  _halfq1 * gx + _halfq3 * gz - _halfq4 * gy;
00672             qDot3 =  _halfq1 * gy - _halfq2 * gz + _halfq4 * gx;
00673             qDot4 =  _halfq1 * gz + _halfq2 * gy - _halfq3 * gx;
00674 
00675             // Compute then integrate estimated quaternion derivative
00676             q1 += (qDot1 -(beta * hatDot1)) * deltat;
00677             q2 += (qDot2 -(beta * hatDot2)) * deltat;
00678             q3 += (qDot3 -(beta * hatDot3)) * deltat;
00679             q4 += (qDot4 -(beta * hatDot4)) * deltat;
00680 
00681             // Normalize the quaternion
00682             norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4);    // normalise quaternion
00683             norm = 1.0f/norm;
00684             q[0] = q1 * norm;
00685             q[1] = q2 * norm;
00686             q[2] = q3 * norm;
00687             q[3] = q4 * norm;
00688             
00689         }
00690 int Init()
00691 {
00692   i2c.frequency(400000);  // use fast (400 kHz) I2C   
00693   
00694   t.start();        
00695   
00696     
00697   // Read the WHO_AM_I register, this is a good test of communication
00698   uint8_t whoami = readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050);  // Read WHO_AM_I register for MPU-6050
00699 //  Serial_2.printf("I AM 0x%x\n\r", whoami); Serial_2.printf("I SHOULD BE 0x68\n\r");
00700   
00701   if (whoami == 0x68) // WHO_AM_I should always be 0x68
00702   {  
00703     //pc.printf("MPU6050 is online...");
00704     wait(1);
00705 
00706     
00707     MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values
00708     //pc.printf("x-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[0]); pc.printf("% of factory value \n\r");
00709 //    pc.printf("y-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[1]); pc.printf("% of factory value \n\r");
00710 //    pc.printf("z-axis self test: acceleration trim within : "); pc.printf("%f", SelfTest[2]); pc.printf("% of factory value \n\r");
00711 //    pc.printf("x-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[3]); pc.printf("% of factory value \n\r");
00712 //    pc.printf("y-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[4]); pc.printf("% of factory value \n\r");
00713 //    pc.printf("z-axis self test: gyration trim within : "); pc.printf("%f", SelfTest[5]); pc.printf("% of factory value \n\r");
00714     wait(1);
00715 
00716     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) 
00717     {
00718     resetMPU6050(); // Reset registers to default in preparation for device calibration
00719     calibrateMPU6050(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers  
00720     initMPU6050(); //pc.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature
00721     wait(2);
00722        }
00723     else
00724     {
00725         //pc.printf("Device did not the pass self-test!\n\r");
00726         return 1;
00727     }
00728     }
00729     else
00730     {
00731 //    pc.printf("Could not connect to MPU6050: \n\r");
00732 //    pc.printf("%#x \n",  whoami);
00733     return 1;
00734 //    while(1) ; // Loop forever if communication doesn't happen
00735   }
00736   return 0;
00737 }
00738     void receiveData(float *yaw, float *pitch , float *roll )
00739   {
00740     if(readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) {  // check if data ready interrupt
00741     readAccelData(accelCount);  // Read the x/y/z adc values
00742     getAres();
00743     
00744     // Now we'll calculate the accleration value into actual g's
00745     ax = (float)accelCount[0]*aRes - accelBias[0];  // get actual g value, this depends on scale being set
00746     ay = (float)accelCount[1]*aRes - accelBias[1];   
00747     az = (float)accelCount[2]*aRes - accelBias[2];  
00748    
00749     readGyroData(gyroCount);  // Read the x/y/z adc values
00750     getGres();
00751  
00752     // Calculate the gyro value into actual degrees per second
00753     gx = (float)gyroCount[0]*gRes; // - gyroBias[0];  // get actual gyro value, this depends on scale being set
00754     gy = (float)gyroCount[1]*gRes; // - gyroBias[1];  
00755     gz = (float)gyroCount[2]*gRes; // - gyroBias[2];   
00756 
00757     tempCount = readTempData();  // Read the x/y/z adc values
00758     temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade
00759    }  
00760    
00761     Now = t.read_us();
00762     deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update
00763     lastUpdate = Now;
00764     
00765  //   sum += deltat;
00766 //    sumCount++;
00767     
00768     if(lastUpdate - firstUpdate > 10000000.0f) {
00769      beta = 0.04;  // decrease filter gain after stabilized
00770      zeta = 0.015; // increasey bias drift gain after stabilized
00771     }
00772     
00773    // Pass gyro rate as rad/s
00774     MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f);
00775 
00776     // Serial print and/or display at 0.5 s rate independent of data rates
00777     delt_t = t.read_ms() - count1;
00778     if (delt_t > 50) { // update LCD once per half-second independent of read rate
00779 
00780 //    pc.printf("ax = %f", 1000*ax); 
00781 //    pc.printf(" ay = %f", 1000*ay); 
00782 //    pc.printf(" az = %f  mg\n\r", 1000*az); 
00783 //
00784 //    pc.printf("gx = %f", gx); 
00785 //    pc.printf(" gy = %f", gy); 
00786 //    pc.printf(" gz = %f  deg/s\n\r", gz); 
00787 //    
00788 //    pc.printf(" temperature = %f  C\n\r", temperature); 
00789 //    
00790 //    pc.printf("q0 = %f\n\r", q[0]);
00791 //    pc.printf("q1 = %f\n\r", q[1]);
00792 //    pc.printf("q2 = %f\n\r", q[2]);
00793 //    pc.printf("q3 = %f\n\r", q[3]);      
00794     
00795     *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]);   
00796     *pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2]));
00797     *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]);
00798     *pitch *= 180.0f / PI;
00799     *yaw   *= 180.0f / PI; 
00800     *roll  *= 180.0f / PI;
00801 
00802     //pc.printf("Yaw, Pitch, Roll: %f %f %f\n\r", yaw, pitch, roll);
00803  
00804     count1 = t.read_ms(); 
00805   } 
00806   }
00807         
00808   
00809   };
00810 
00811 #endif