This one compatable with brobot V3. first commit to BroBot

Dependencies:   I2Cdev

Dependents:   BroBot_ESE350_Skeleton

Fork of MPU6050 by Carter Sharer

Revision:
6:f38dfe62d74c
Parent:
3:25e1a5a10e53
Child:
7:d5845b617139
diff -r 7d1bf3ce0053 -r f38dfe62d74c MPU6050.h
--- a/MPU6050.h	Sat Nov 23 16:47:00 2013 +0000
+++ b/MPU6050.h	Sat Jan 30 17:12:45 2016 +0000
@@ -1,9 +1,3 @@
-//ported from arduino library: https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
-//written by szymon gaertig (email: szymon@gaertig.com.pl)
-//
-//Changelog: 
-//2013-01-08 - first beta release
-
 // I2Cdev library collection - MPU6050 I2C device class
 // Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
 // 10/3/2011 by Jeff Rowberg <jeff@rowberg.net>
@@ -44,7 +38,19 @@
 #define _MPU6050_H_
 
 #include "I2Cdev.h"
-#include "helper_3dmath.h"
+
+// supporting link:  http://forum.arduino.cc/index.php?&topic=143444.msg1079517#msg1079517
+// also: http://forum.arduino.cc/index.php?&topic=141571.msg1062899#msg1062899s
+#ifndef __arm__
+#include <avr/pgmspace.h>
+#else
+#define PROGMEM /* empty */
+#define pgm_read_byte(x) (*(x))
+#define pgm_read_word(x) (*(x))
+#define pgm_read_float(x) (*(x))
+#define PSTR(STR) STR
+#endif
+
 
 #define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
 #define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
@@ -102,32 +108,20 @@
 #define MPU6050_RA_INT_ENABLE       0x38
 #define MPU6050_RA_DMP_INT_STATUS   0x39
 #define MPU6050_RA_INT_STATUS       0x3A
-
 #define MPU6050_RA_ACCEL_XOUT_H     0x3B
 #define MPU6050_RA_ACCEL_XOUT_L     0x3C
 #define MPU6050_RA_ACCEL_YOUT_H     0x3D
 #define MPU6050_RA_ACCEL_YOUT_L     0x3E
 #define MPU6050_RA_ACCEL_ZOUT_H     0x3F
 #define MPU6050_RA_ACCEL_ZOUT_L     0x40
-
 #define MPU6050_RA_TEMP_OUT_H       0x41
 #define MPU6050_RA_TEMP_OUT_L       0x42
-
 #define MPU6050_RA_GYRO_XOUT_H      0x43
 #define MPU6050_RA_GYRO_XOUT_L      0x44
 #define MPU6050_RA_GYRO_YOUT_H      0x45
 #define MPU6050_RA_GYRO_YOUT_L      0x46
 #define MPU6050_RA_GYRO_ZOUT_H      0x47
 #define MPU6050_RA_GYRO_ZOUT_L      0x48
-
-#define MPU9150_RA_MAG_ADDRESS      0x0C
-#define MPU9150_RA_MAG_XOUT_L       0x03
-#define MPU9150_RA_MAG_XOUT_H       0x04
-#define MPU9150_RA_MAG_YOUT_L       0x05
-#define MPU9150_RA_MAG_YOUT_H       0x06
-#define MPU9150_RA_MAG_ZOUT_L       0x07
-#define MPU9150_RA_MAG_ZOUT_H       0x08
-
 #define MPU6050_RA_EXT_SENS_DATA_00 0x49
 #define MPU6050_RA_EXT_SENS_DATA_01 0x4A
 #define MPU6050_RA_EXT_SENS_DATA_02 0x4B
@@ -416,8 +410,7 @@
 
 class MPU6050 {
     private:
-        I2Cdev i2Cdev;
-        Serial debugSerial;
+        I2Cdev i2cdev;
     public:
         MPU6050();
         MPU6050(uint8_t address);
@@ -617,6 +610,7 @@
         uint32_t getExternalSensorDWord(int position);
 
         // MOT_DETECT_STATUS register
+        uint8_t getMotionStatus();
         bool getXNegMotionDetected();
         bool getXPosMotionDetected();
         bool getYNegMotionDetected();
@@ -701,16 +695,16 @@
         // XG_OFFS_TC register
         uint8_t getOTPBankValid();
         void setOTPBankValid(bool enabled);
-        int8_t getXGyroOffset();
-        void setXGyroOffset(int8_t offset);
+        int8_t getXGyroOffsetTC();
+        void setXGyroOffsetTC(int8_t offset);
 
         // YG_OFFS_TC register
-        int8_t getYGyroOffset();
-        void setYGyroOffset(int8_t offset);
+        int8_t getYGyroOffsetTC();
+        void setYGyroOffsetTC(int8_t offset);
 
         // ZG_OFFS_TC register
-        int8_t getZGyroOffset();
-        void setZGyroOffset(int8_t offset);
+        int8_t getZGyroOffsetTC();
+        void setZGyroOffsetTC(int8_t offset);
 
         // X_FINE_GAIN register
         int8_t getXFineGain();
@@ -737,16 +731,16 @@
         void setZAccelOffset(int16_t offset);
 
         // XG_OFFS_USR* registers
-        int16_t getXGyroOffsetUser();
-        void setXGyroOffsetUser(int16_t offset);
+        int16_t getXGyroOffset();
+        void setXGyroOffset(int16_t offset);
 
         // YG_OFFS_USR* register
-        int16_t getYGyroOffsetUser();
-        void setYGyroOffsetUser(int16_t offset);
+        int16_t getYGyroOffset();
+        void setYGyroOffset(int16_t offset);
 
         // ZG_OFFS_USR* register
-        int16_t getZGyroOffsetUser();
-        void setZGyroOffsetUser(int16_t offset);
+        int16_t getZGyroOffset();
+        void setZGyroOffset(int16_t offset);
         
         // INT_ENABLE register (DMP functions)
         bool getIntPLLReadyEnabled();