Thanks Erik Olieman for his beta library, that saved me a huge amount of time when getting Raw data from MPU6050 module! I was able to update this library by adding additional functions, which would allow a fast angle calculation by using complementary filter. I will probably be updating this library more soon to add additional functionality or make some changes that would look sensible.

Dependents:   QuadcopterProgram 3DTracking ControlYokutan2017 Gyro ... more

Fork of MPU6050 by Erik -

Revision:
8:b1570b99df9e
Parent:
7:56e591a74939
Child:
9:898effccce30
--- a/MPU6050.cpp	Fri Feb 13 01:04:17 2015 +0000
+++ b/MPU6050.cpp	Fri Feb 13 01:16:00 2015 +0000
@@ -202,6 +202,21 @@
     angle[Z_AXIS] = angle[Z_AXIS] + GYRO_SCALE*gyro[Z_AXIS]*(*currTime-*prevTime);  //this is Yaw hopefully :D
     //Y = atan2(rawY,rawZ) * 180 / PI;  //This spits out values between -180 to 180 (360 degrees)    
 }
+
+void MPU6050::enableInt( void )
+{
+    char temp;
+    temp = this->read(MPU6050_RA_INT_ENABLE);
+    temp |= 0x01;
+    this->write(MPU6050_RA_INT_ENABLE, temp);
+}
+void MPU6050::disableInt ( void )
+{
+    char temp;
+    temp = this->read(MPU6050_RA_INT_ENABLE);
+    temp &= 0xFE;
+    this->write(MPU6050_RA_INT_ENABLE, temp);
+}
 //--------------------------------------------------
 //------------------Gyroscope-----------------------
 //--------------------------------------------------