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.
Revision 0:e63996fd7d3e, committed 2015-07-03
- Comitter:
- khaledelmadawi
- Date:
- Fri Jul 03 11:16:02 2015 +0000
- Commit message:
- Quadcopter Attitude Control(Yaw-Pitch-Roll)
Changed in this revision
diff -r 000000000000 -r e63996fd7d3e AngularDataAcquizition.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/AngularDataAcquizition.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,181 @@
+#ifndef MBED_AngularDataAcquizition_H
+#define MBED_AngularDataAcquizition_H
+
+#include "I2Cdev.h"
+#include "mbed.h"
+#include "MPU6050_6Axis_MotionApps20.h" // works
+#include <math.h>
+
+#ifndef M_PI
+#define M_PI 3.1415
+#endif
+#define D_BAUDRATE 115200
+
+class AngularDataAcquizition{
+ public:
+ AngularDataAcquizition(PinName D_SDA, PinName D_SCL);
+ void BeginInterrupt(float InterruptDuration);
+ void StopInterrupt();
+ void UpdateTheta();
+ void MeanValue(float *FilteredVal, int num);
+ void FilterVariablesAquizition(float *variable,int number);
+ void callMeanFilteredReadings();
+
+ float Meanypr[3];
+ bool dmpReady; // set true if DMP init was successful
+
+ private:
+ I2C _i2c;
+ MPU6050 mpuLocal;
+ Ticker timer;
+ uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
+ uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
+ uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
+ uint16_t fifoCount; // count of all bytes currently in FIFO
+ uint8_t fifoBuffer[64]; // FIFO storage buffer
+ // orientation/motion vars
+ Quaternion q; // [w, x, y, z] quaternion container
+ VectorInt16 aa; // [x, y, z] accel sensor measurements
+ VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
+ VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements
+ VectorFloat gravity; // [x, y, z] gravity vector
+ float euler[3]; // [psi, theta, phi] Euler angle container
+ float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
+ Serial pc;
+ // packet structure for InvenSense teapot demo
+ uint8_t teapotPacket[15];
+
+ };
+
+
+
+
+
+
+
+AngularDataAcquizition::AngularDataAcquizition(PinName D_SDA, PinName D_SCL): _i2c(D_SDA, D_SCL),pc(USBTX, USBRX) {
+ dmpReady = false;
+ teapotPacket[0] = '$',teapotPacket[1] = 0x02,teapotPacket[2] = 0,teapotPacket[3] = 0,teapotPacket[4] = 0,teapotPacket[5] = 0,teapotPacket[6] = 0,
+ teapotPacket[7] = 0,teapotPacket[8] = 0,teapotPacket[9] = 0,teapotPacket[10] = 0x00,teapotPacket[11] = 0x00,teapotPacket[12] = '\r',teapotPacket[13] = '\n',teapotPacket[14] = 0 ;
+ //Serial pc(USBTX, USBRX); // tx, rx
+
+ pc.baud(D_BAUDRATE);
+ // initialize device
+ pc.printf("Initializing I2C devices...\n");
+ mpuLocal.initialize();
+ // verify connection
+ pc.printf("Testing device connections...\n");
+
+ bool mpu6050TestResult = mpuLocal.testConnection();
+ if(mpu6050TestResult){
+ pc.printf("mpuLocalLocalLocal6050 test passed \n");
+ } else{
+ pc.printf("mpuLocalLocalLocal6050 test failed \n");
+ }
+
+ // wait for ready
+ pc.printf("\nSend any character to begin DMP programming and demo: ");
+
+ //while(!pc.readable());
+ // pc.getc();
+ pc.printf("\n");
+
+ // load and configure the DMP
+ pc.printf("Initializing DMP...\n");
+ devStatus = mpuLocal.dmpInitialize();
+
+ // supply your own gyro offsets here, scaled for min sensitivity
+ mpuLocal.setXGyroOffset(-61);
+ mpuLocal.setYGyroOffset(-127);
+ mpuLocal.setZGyroOffset(19);
+ mpuLocal.setZAccelOffset(16282); // 1688 factory default for my test chip
+
+ // make sure it worked (returns 0 if so)
+ if (devStatus == 0) {
+ // turn on the DMP, now that it's ready
+ pc.printf("Enabling DMP...\n");
+ mpuLocal.setDMPEnabled(true);
+
+ // enable Arduino interrupt detection
+ pc.printf("Enabling interrupt detection (Arduino external interrupt 0)...\n");
+// attachInterrupt(0, dmpDataReady, RISING);
+ mpuIntStatus = mpuLocal.getIntStatus();
+
+ // set our DMP Ready flag so the main loop() function knows it's okay to use it
+ pc.printf("DMP ready! Waiting for first interrupt...\n");
+ dmpReady = true;
+
+ // get expected DMP packet size for later comparison
+ packetSize = mpuLocal.dmpGetFIFOPacketSize();
+ } else {
+ // ERROR!
+ // 1 = initial memory load failed
+ // 2 = DMP configuration updates failed
+ // (if it's going to break, usually the code will be 1)
+ pc.printf("DMP Initialization failed (code ");
+ pc.printf("%u",devStatus);
+ pc.printf(")\n");
+ }
+
+
+}
+
+void AngularDataAcquizition::UpdateTheta(){
+ // reset interrupt flag and get INT_STATUS byte
+ mpuIntStatus = mpuLocal.getIntStatus();
+
+ // get current FIFO count
+ fifoCount = mpuLocal.getFIFOCount();
+
+ // check for overflow (this should never happen unless our code is too inefficient)
+ if ((mpuIntStatus & 0x10) || fifoCount == 1024) {
+ // reset so we can continue cleanly
+ mpuLocal.resetFIFO();
+ pc.printf("FIFO overflow!");
+
+ // otherwise, check for DMP data ready interrupt (this should happen frequently)
+ } else if (mpuIntStatus & 0x02) {
+ // wait for correct available data length, should be a VERY short wait
+ while (fifoCount < packetSize) fifoCount = mpuLocal.getFIFOCount();
+
+ // read a packet from FIFO
+ mpuLocal.getFIFOBytes(fifoBuffer, packetSize);
+
+ // track FIFO count here in case there is > 1 packet available
+ // (this lets us immediately read more without waiting for an interrupt)
+ fifoCount -= packetSize;
+ // display Euler angles in degrees
+ mpuLocal.dmpGetQuaternion(&q, fifoBuffer);
+ mpuLocal.dmpGetGravity(&gravity, &q);
+ mpuLocal.dmpGetYawPitchRoll(ypr, &q, &gravity);
+ }
+}
+void AngularDataAcquizition::MeanValue(float *FilteredVal, int num){
+ int i,j;
+ for(j=0;j<3;j++)
+ FilteredVal[j]=0;
+ for (i=0;i<num;i++){
+ UpdateTheta();
+ for(j=0;j<3;j++)
+ FilteredVal[j]=FilteredVal[j]+ypr[j];
+ }
+ for(j=0;j<3;j++)
+ FilteredVal[j]=FilteredVal[j]/num;
+}
+void AngularDataAcquizition::callMeanFilteredReadings(){
+ MeanValue(Meanypr,20);
+ Meanypr[1]=Meanypr[1]-(1.19284-0.00716-0.7679)*3.14/180;
+ Meanypr[2]=Meanypr[2]-(-0.96533+0.021043+0.107681)*3.14/180;
+
+}
+void AngularDataAcquizition::BeginInterrupt(float InterruptDuration){
+ if(dmpReady)
+ timer.attach(this,&AngularDataAcquizition::callMeanFilteredReadings, InterruptDuration);
+ }
+void AngularDataAcquizition::StopInterrupt(){
+ if(dmpReady)
+ timer.detach();
+ }
+
+#endif
+
diff -r 000000000000 -r e63996fd7d3e Counter.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Counter.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,66 @@
+#include "Counter.h"
+
+
+
+Counter::Counter(PinName channel,
+ float inc_enc_constant) : _interrupt(channel) // create the InterruptIn on the pin specified to Counter
+{
+ _interrupt.fall(this, &Counter::increment); // attach increment function of this counter instance
+ delta_time = 0;
+ rpm = 0;
+ t.start();
+ _inc_enc_constant=inc_enc_constant;
+}
+
+void Counter::increment()
+{
+ delta_time = t.read_us();
+ t.reset();
+ rpm = ( _inc_enc_constant / (delta_time/1000000) ) *60 ; // rev / m
+
+ _count++;
+
+}
+
+int Counter::read_count()
+{
+ return _count;
+}
+float Counter::read_rpm()
+{
+ return rpm;
+}
+void Counter::reset()
+{
+ rpm=0;
+ _count=0;
+}
+
+float Counter::medianFilter(int Window_Size)
+{
+ float *array;
+ float return_val;
+ int i,j,return_idx;
+ array=(float*)malloc(sizeof(float)*Window_Size);
+ for (i=0; i<Window_Size; i++) {
+ array[i]=read_rpm();
+ if(i>0) {
+ for (j=0; j<i; j++) {
+ if(array[j]<array[i]) {
+ swap(&array[j],&array[i]);
+ }
+ }
+ }
+
+ }
+ delete array;
+ return_idx=Window_Size/2;
+ return_val=array[return_idx];
+ return return_val;
+}
+void Counter::swap(float *x,float *y){
+ float z;
+ z=*x;
+ *x=*y;
+ *y=z;
+}
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e Counter.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Counter.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,24 @@
+#ifndef Counter_H
+#define Counter_H
+#include "mbed.h"
+class Counter {
+
+public:
+Counter(PinName channel,float inc_enc_constant);
+void increment();
+int read_count();
+float read_rpm();
+void reset();
+float medianFilter(int Window_Size);
+void swap(float *x,float *y);
+
+private:
+ long float delta_time;
+ float rpm;
+ InterruptIn _interrupt;
+ Timer t;
+ volatile int _count;
+ float _inc_enc_constant;
+};
+
+#endif /* Counter_H */
diff -r 000000000000 -r e63996fd7d3e I2Cdev.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/I2Cdev.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,275 @@
+// ported from arduino library: https://github.com/jrowberg/i2cdevlib
+// written by szymon gaertig (email: szymon@gaertig.com.pl, website: szymongaertig.pl)
+// Changelog:
+// 2013-01-08 - first release
+
+#include "I2Cdev.h"
+
+#define useDebugSerial
+
+I2Cdev::I2Cdev(): i2c(I2C_SDA,I2C_SCL), debugSerial(USBTX, USBRX)
+{
+
+}
+
+I2Cdev::I2Cdev(PinName i2cSda, PinName i2cScl): i2c(i2cSda,i2cScl), debugSerial(USBTX, USBRX)
+{
+
+}
+
+/** Read a single bit from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-7)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout) {
+ uint8_t b;
+ uint8_t count = readByte(devAddr, regAddr, &b, timeout);
+ *data = b & (1 << bitNum);
+ return count;
+}
+
+/** Read a single bit from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitNum Bit position to read (0-15)
+ * @param data Container for single bit value
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout) {
+ uint16_t b;
+ uint8_t count = readWord(devAddr, regAddr, &b, timeout);
+ *data = b & (1 << bitNum);
+ return count;
+}
+
+/** Read multiple bits from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-7)
+ * @param length Number of bits to read (not more than 8)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout) {
+ // 01101001 read byte
+ // 76543210 bit numbers
+ // xxx args: bitStart=4, length=3
+ // 010 masked
+ // -> 010 shifted
+ uint8_t count, b;
+ if ((count = readByte(devAddr, regAddr, &b, timeout)) != 0) {
+ uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+ b &= mask;
+ b >>= (bitStart - length + 1);
+ *data = b;
+ }
+ return count;
+}
+
+/** Read multiple bits from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param bitStart First bit position to read (0-15)
+ * @param length Number of bits to read (not more than 16)
+ * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05)
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (1 = success, 0 = failure, -1 = timeout)
+ */
+int8_t I2Cdev::readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout) {
+ // 1101011001101001 read byte
+ // fedcba9876543210 bit numbers
+ // xxx args: bitStart=12, length=3
+ // 010 masked
+ // -> 010 shifted
+ uint8_t count;
+ uint16_t w;
+ if ((count = readWord(devAddr, regAddr, &w, timeout)) != 0) {
+ uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+ w &= mask;
+ w >>= (bitStart - length + 1);
+ *data = w;
+ }
+ return count;
+}
+/** Read single byte from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for byte value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout) {
+ return readBytes(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read single word from a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to read from
+ * @param data Container for word value read from device
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Status of read operation (true = success)
+ */
+int8_t I2Cdev::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout) {
+ return readWords(devAddr, regAddr, 1, data, timeout);
+}
+
+/** Read multiple bytes from an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr First register regAddr to read from
+ * @param length Number of bytes to read
+ * @param data Buffer to store read data in
+ * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout)
+ * @return Number of bytes read (-1 indicates failure)
+ */
+int8_t I2Cdev::readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout)
+{
+ char command[1];
+ command[0] = regAddr;
+ char *redData = (char*)malloc(length);
+ i2c.write(devAddr<<1, command, 1, true);
+ i2c.read(devAddr<<1, redData, length);
+ for(int i =0; i < length; i++) {
+ data[i] = redData[i];
+ }
+ free (redData);
+ return length;
+}
+
+int8_t I2Cdev::readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout)
+{
+ return 0;
+}
+
+/** write a single bit in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-7)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) {
+ uint8_t b;
+ readByte(devAddr, regAddr, &b);
+ b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum));
+ return writeByte(devAddr, regAddr, b);
+}
+
+/** write a single bit in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitNum Bit position to write (0-15)
+ * @param value New bit value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data) {
+ uint16_t w;
+ readWord(devAddr, regAddr, &w);
+ w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum));
+ return writeWord(devAddr, regAddr, w);
+}
+
+/** Write multiple bits in an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-7)
+ * @param length Number of bits to write (not more than 8)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) {
+ // 010 value to write
+ // 76543210 bit numbers
+ // xxx args: bitStart=4, length=3
+ // 00011100 mask byte
+ // 10101111 original value (sample)
+ // 10100011 original & ~mask
+ // 10101011 masked | value
+ uint8_t b;
+ if (readByte(devAddr, regAddr, &b) != 0) {
+ uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+ data <<= (bitStart - length + 1); // shift data into correct position
+ data &= mask; // zero all non-important bits in data
+ b &= ~(mask); // zero all important bits in existing byte
+ b |= data; // combine data with existing byte
+ return writeByte(devAddr, regAddr, b);
+ } else {
+ return false;
+ }
+}
+
+/** Write multiple bits in a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register regAddr to write to
+ * @param bitStart First bit position to write (0-15)
+ * @param length Number of bits to write (not more than 16)
+ * @param data Right-aligned value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data) {
+ // 010 value to write
+ // fedcba9876543210 bit numbers
+ // xxx args: bitStart=12, length=3
+ // 0001110000000000 mask byte
+ // 1010111110010110 original value (sample)
+ // 1010001110010110 original & ~mask
+ // 1010101110010110 masked | value
+ uint16_t w;
+ if (readWord(devAddr, regAddr, &w) != 0) {
+ uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
+ data <<= (bitStart - length + 1); // shift data into correct position
+ data &= mask; // zero all non-important bits in data
+ w &= ~(mask); // zero all important bits in existing word
+ w |= data; // combine data with existing word
+ return writeWord(devAddr, regAddr, w);
+ } else {
+ return false;
+ }
+}
+
+/** Write single byte to an 8-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New byte value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) {
+ return writeBytes(devAddr, regAddr, 1, &data);
+}
+
+/** Write single word to a 16-bit device register.
+ * @param devAddr I2C slave device address
+ * @param regAddr Register address to write to
+ * @param data New word value to write
+ * @return Status of operation (true = success)
+ */
+bool I2Cdev::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) {
+ return writeWords(devAddr, regAddr, 1, &data);
+}
+
+bool I2Cdev::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
+{
+ i2c.start();
+ i2c.write(devAddr<<1);
+ i2c.write(regAddr);
+ for(int i = 0; i < length; i++) {
+ i2c.write(data[i]);
+ }
+ i2c.stop();
+ return true;
+}
+
+bool I2Cdev::writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data)
+{
+ return true;
+}
+
+uint16_t I2Cdev::readTimeout(void)
+{
+ return 0;
+}
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e I2Cdev.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/I2Cdev.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,44 @@
+//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
+
+#ifndef I2Cdev_h
+#define I2Cdev_h
+
+#include "mbed.h"
+
+#define I2C_SDA p9
+#define I2C_SCL p10
+
+class I2Cdev {
+ private:
+ I2C i2c;
+ Serial debugSerial;
+ public:
+ I2Cdev();
+ I2Cdev(PinName i2cSda, PinName i2cScl);
+
+ int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout());
+ int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout());
+
+ bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data);
+ bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data);
+ bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
+ bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data);
+ bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
+ bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data);
+ bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data);
+ bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data);
+
+ static uint16_t readTimeout(void);
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e MPU6050.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU6050.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,3442 @@
+//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)
+// 8/24/2011 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#include "MPU6050.h"
+
+#define useDebugSerial
+
+//instead of using pgmspace.h
+typedef const unsigned char prog_uchar;
+#define pgm_read_byte_near(x) (*(prog_uchar*)(x))//<- I modified here
+#define pgm_read_byte(x) (*(prog_uchar*)(x))//<- I modified here
+
+/** Default constructor, uses default I2C address.
+ * @see MPU6050_DEFAULT_ADDRESS
+ */
+MPU6050::MPU6050() : debugSerial(USBTX, USBRX)
+{
+ devAddr = MPU6050_DEFAULT_ADDRESS;
+}
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see MPU6050_DEFAULT_ADDRESS
+ * @see MPU6050_ADDRESS_AD0_LOW
+ * @see MPU6050_ADDRESS_AD0_HIGH
+ */
+MPU6050::MPU6050(uint8_t address) : debugSerial(USBTX, USBRX)
+{
+ devAddr = address;
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU6050::initialize()
+{
+
+#ifdef useDebugSerial
+ debugSerial.printf("MPU6050::initialize start\n");
+#endif
+
+ setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+ setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+ setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+ setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+
+#ifdef useDebugSerial
+ debugSerial.printf("MPU6050::initialize end\n");
+#endif
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool MPU6050::testConnection()
+{
+#ifdef useDebugSerial
+ debugSerial.printf("MPU6050::testConnection start\n");
+#endif
+ uint8_t deviceId = getDeviceID();
+#ifdef useDebugSerial
+ debugSerial.printf("DeviceId = %d\n",deviceId);
+#endif
+ return deviceId == 0x34;
+}
+
+// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC)
+
+/** Get the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @return I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+uint8_t MPU6050::getAuxVDDIOLevel()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer);
+ return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void MPU6050::setAuxVDDIOLevel(uint8_t level)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level);
+}
+
+// SMPLRT_DIV register
+
+/** Get gyroscope output rate divider.
+ * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero
+ * Motion detection, and Free Fall detection are all based on the Sample Rate.
+ * The Sample Rate is generated by dividing the gyroscope output rate by
+ * SMPLRT_DIV:
+ *
+ * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV)
+ *
+ * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or
+ * 7), and 1kHz when the DLPF is enabled (see Register 26).
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * For a diagram of the gyroscope and accelerometer signal paths, see Section 8
+ * of the MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+uint8_t MPU6050::getRate()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer);
+ return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU6050_RA_SMPLRT_DIV
+ */
+void MPU6050::setRate(uint8_t rate)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate);
+}
+
+// CONFIG register
+
+/** Get external FSYNC configuration.
+ * Configures the external Frame Synchronization (FSYNC) pin sampling. An
+ * external signal connected to the FSYNC pin can be sampled by configuring
+ * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short
+ * strobes may be captured. The latched FSYNC signal will be sampled at the
+ * Sampling Rate, as defined in register 25. After sampling, the latch will
+ * reset to the current FSYNC signal state.
+ *
+ * The sampled value will be reported in place of the least significant bit in
+ * a sensor data register determined by the value of EXT_SYNC_SET according to
+ * the following table.
+ *
+ * <pre>
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0 | Input disabled
+ * 1 | TEMP_OUT_L[0]
+ * 2 | GYRO_XOUT_L[0]
+ * 3 | GYRO_YOUT_L[0]
+ * 4 | GYRO_ZOUT_L[0]
+ * 5 | ACCEL_XOUT_L[0]
+ * 6 | ACCEL_YOUT_L[0]
+ * 7 | ACCEL_ZOUT_L[0]
+ * </pre>
+ *
+ * @return FSYNC configuration value
+ */
+uint8_t MPU6050::getExternalFrameSync()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set external FSYNC configuration.
+ * @see getExternalFrameSync()
+ * @see MPU6050_RA_CONFIG
+ * @param sync New FSYNC configuration value
+ */
+void MPU6050::setExternalFrameSync(uint8_t sync)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync);
+}
+/** Get digital low-pass filter configuration.
+ * The DLPF_CFG parameter sets the digital low pass filter configuration. It
+ * also determines the internal sampling rate used by the device as shown in
+ * the table below.
+ *
+ * Note: The accelerometer output rate is 1kHz. This means that for a Sample
+ * Rate greater than 1kHz, the same accelerometer sample may be output to the
+ * FIFO, DMP, and sensor registers more than once.
+ *
+ * <pre>
+ * | ACCELEROMETER | GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay | Bandwidth | Delay | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0 | 260Hz | 0ms | 256Hz | 0.98ms | 8kHz
+ * 1 | 184Hz | 2.0ms | 188Hz | 1.9ms | 1kHz
+ * 2 | 94Hz | 3.0ms | 98Hz | 2.8ms | 1kHz
+ * 3 | 44Hz | 4.9ms | 42Hz | 4.8ms | 1kHz
+ * 4 | 21Hz | 8.5ms | 20Hz | 8.3ms | 1kHz
+ * 5 | 10Hz | 13.8ms | 10Hz | 13.4ms | 1kHz
+ * 6 | 5Hz | 19.0ms | 5Hz | 18.6ms | 1kHz
+ * 7 | -- Reserved -- | -- Reserved -- | Reserved
+ * </pre>
+ *
+ * @return DLFP configuration
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+uint8_t MPU6050::getDLPFMode()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set digital low-pass filter configuration.
+ * @param mode New DLFP configuration setting
+ * @see getDLPFBandwidth()
+ * @see MPU6050_DLPF_BW_256
+ * @see MPU6050_RA_CONFIG
+ * @see MPU6050_CFG_DLPF_CFG_BIT
+ * @see MPU6050_CFG_DLPF_CFG_LENGTH
+ */
+void MPU6050::setDLPFMode(uint8_t mode)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode);
+}
+
+// GYRO_CONFIG register
+
+/** Get full-scale gyroscope range.
+ * The FS_SEL parameter allows setting the full-scale range of the gyro sensors,
+ * as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * </pre>
+ *
+ * @return Current full-scale gyroscope range setting
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+uint8_t MPU6050::getFullScaleGyroRange()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set full-scale gyroscope range.
+ * @param range New full-scale gyroscope range value
+ * @see getFullScaleRange()
+ * @see MPU6050_GYRO_FS_250
+ * @see MPU6050_RA_GYRO_CONFIG
+ * @see MPU6050_GCONFIG_FS_SEL_BIT
+ * @see MPU6050_GCONFIG_FS_SEL_LENGTH
+ */
+void MPU6050::setFullScaleGyroRange(uint8_t range)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range);
+}
+
+// ACCEL_CONFIG register
+
+/** Get self-test enabled setting for accelerometer X axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelXSelfTest()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer);
+ return buffer[0];
+}
+/** Get self-test enabled setting for accelerometer X axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelXSelfTest(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelYSelfTest()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer);
+ return buffer[0];
+}
+/** Get self-test enabled value for accelerometer Y axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelYSelfTest(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled);
+}
+/** Get self-test enabled value for accelerometer Z axis.
+ * @return Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+bool MPU6050::getAccelZSelfTest()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer);
+ return buffer[0];
+}
+/** Set self-test enabled value for accelerometer Z axis.
+ * @param enabled Self-test enabled value
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setAccelZSelfTest(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled);
+}
+/** Get full-scale accelerometer range.
+ * The FS_SEL parameter allows setting the full-scale range of the accelerometer
+ * sensors, as described in the table below.
+ *
+ * <pre>
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * </pre>
+ *
+ * @return Current full-scale accelerometer range setting
+ * @see MPU6050_ACCEL_FS_2
+ * @see MPU6050_RA_ACCEL_CONFIG
+ * @see MPU6050_ACONFIG_AFS_SEL_BIT
+ * @see MPU6050_ACONFIG_AFS_SEL_LENGTH
+ */
+uint8_t MPU6050::getFullScaleAccelRange()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set full-scale accelerometer range.
+ * @param range New full-scale accelerometer range setting
+ * @see getFullScaleAccelRange()
+ */
+void MPU6050::setFullScaleAccelRange(uint8_t range)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range);
+}
+/** Get the high-pass filter configuration.
+ * The DHPF is a filter module in the path leading to motion detectors (Free
+ * Fall, Motion threshold, and Zero Motion). The high pass filter output is not
+ * available to the data registers (see Figure in Section 8 of the MPU-6000/
+ * MPU-6050 Product Specification document).
+ *
+ * The high pass filter has three modes:
+ *
+ * <pre>
+ * Reset: The filter output settles to zero within one sample. This
+ * effectively disables the high pass filter. This mode may be toggled
+ * to quickly settle the filter.
+ *
+ * On: The high pass filter will pass signals above the cut off frequency.
+ *
+ * Hold: When triggered, the filter holds the present sample. The filter
+ * output will be the difference between the input sample and the held
+ * sample.
+ * </pre>
+ *
+ * <pre>
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0 | Reset | None
+ * 1 | On | 5Hz
+ * 2 | On | 2.5Hz
+ * 3 | On | 1.25Hz
+ * 4 | On | 0.63Hz
+ * 7 | Hold | None
+ * </pre>
+ *
+ * @return Current high-pass filter configuration
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+uint8_t MPU6050::getDHPFMode()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set the high-pass filter configuration.
+ * @param bandwidth New high-pass filter configuration
+ * @see setDHPFMode()
+ * @see MPU6050_DHPF_RESET
+ * @see MPU6050_RA_ACCEL_CONFIG
+ */
+void MPU6050::setDHPFMode(uint8_t bandwidth)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth);
+}
+
+// FF_THR register
+
+/** Get free-fall event acceleration threshold.
+ * This register configures the detection threshold for Free Fall event
+ * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the
+ * absolute value of the accelerometer measurements for the three axes are each
+ * less than the detection threshold. This condition increments the Free Fall
+ * duration counter (Register 30). The Free Fall interrupt is triggered when the
+ * Free Fall duration counter reaches the time specified in FF_DUR.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current free-fall acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_FF_THR
+ */
+uint8_t MPU6050::getFreefallDetectionThreshold()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_FF_THR, buffer);
+ return buffer[0];
+}
+/** Get free-fall event acceleration threshold.
+ * @param threshold New free-fall acceleration threshold value (LSB = 2mg)
+ * @see getFreefallDetectionThreshold()
+ * @see MPU6050_RA_FF_THR
+ */
+void MPU6050::setFreefallDetectionThreshold(uint8_t threshold)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_FF_THR, threshold);
+}
+
+// FF_DUR register
+
+/** Get free-fall event duration threshold.
+ * This register configures the duration counter threshold for Free Fall event
+ * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit
+ * of 1 LSB = 1 ms.
+ *
+ * The Free Fall duration counter increments while the absolute value of the
+ * accelerometer measurements are each less than the detection threshold
+ * (Register 29). The Free Fall interrupt is triggered when the Free Fall
+ * duration counter reaches the time specified in this register.
+ *
+ * For more details on the Free Fall detection interrupt, see Section 8.2 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current free-fall duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_FF_DUR
+ */
+uint8_t MPU6050::getFreefallDetectionDuration()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_FF_DUR, buffer);
+ return buffer[0];
+}
+/** Get free-fall event duration threshold.
+ * @param duration New free-fall duration threshold value (LSB = 1ms)
+ * @see getFreefallDetectionDuration()
+ * @see MPU6050_RA_FF_DUR
+ */
+void MPU6050::setFreefallDetectionDuration(uint8_t duration)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_FF_DUR, duration);
+}
+
+// MOT_THR register
+
+/** Get motion detection event acceleration threshold.
+ * This register configures the detection threshold for Motion interrupt
+ * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the
+ * absolute value of any of the accelerometer measurements exceeds this Motion
+ * detection threshold. This condition increments the Motion detection duration
+ * counter (Register 32). The Motion detection interrupt is triggered when the
+ * Motion Detection counter reaches the time count specified in MOT_DUR
+ * (Register 32).
+ *
+ * The Motion interrupt will indicate the axis and polarity of detected motion
+ * in MOT_DETECT_STATUS (Register 97).
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and
+ * 58 of this document.
+ *
+ * @return Current motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_MOT_THR
+ */
+uint8_t MPU6050::getMotionDetectionThreshold()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_MOT_THR, buffer);
+ return buffer[0];
+}
+/** Set free-fall event acceleration threshold.
+ * @param threshold New motion detection acceleration threshold value (LSB = 2mg)
+ * @see getMotionDetectionThreshold()
+ * @see MPU6050_RA_MOT_THR
+ */
+void MPU6050::setMotionDetectionThreshold(uint8_t threshold)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_THR, threshold);
+}
+
+// MOT_DUR register
+
+/** Get motion detection event duration threshold.
+ * This register configures the duration counter threshold for Motion interrupt
+ * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit
+ * of 1LSB = 1ms. The Motion detection duration counter increments when the
+ * absolute value of any of the accelerometer measurements exceeds the Motion
+ * detection threshold (Register 31). The Motion detection interrupt is
+ * triggered when the Motion detection counter reaches the time count specified
+ * in this register.
+ *
+ * For more details on the Motion detection interrupt, see Section 8.3 of the
+ * MPU-6000/MPU-6050 Product Specification document.
+ *
+ * @return Current motion detection duration threshold value (LSB = 1ms)
+ * @see MPU6050_RA_MOT_DUR
+ */
+uint8_t MPU6050::getMotionDetectionDuration()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_MOT_DUR, buffer);
+ return buffer[0];
+}
+/** Set motion detection event duration threshold.
+ * @param duration New motion detection duration threshold value (LSB = 1ms)
+ * @see getMotionDetectionDuration()
+ * @see MPU6050_RA_MOT_DUR
+ */
+void MPU6050::setMotionDetectionDuration(uint8_t duration)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_MOT_DUR, duration);
+}
+
+// ZRMOT_THR register
+
+/** Get zero motion detection event acceleration threshold.
+ * This register configures the detection threshold for Zero Motion interrupt
+ * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when
+ * the absolute value of the accelerometer measurements for the 3 axes are each
+ * less than the detection threshold. This condition increments the Zero Motion
+ * duration counter (Register 34). The Zero Motion interrupt is triggered when
+ * the Zero Motion duration counter reaches the time count specified in
+ * ZRMOT_DUR (Register 34).
+ *
+ * Unlike Free Fall or Motion detection, Zero Motion detection triggers an
+ * interrupt both when Zero Motion is first detected and when Zero Motion is no
+ * longer detected.
+ *
+ * When a zero motion event is detected, a Zero Motion Status will be indicated
+ * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion
+ * condition is detected, the status bit is set to 1. When a zero-motion-to-
+ * motion condition is detected, the status bit is set to 0.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+uint8_t MPU6050::getZeroMotionDetectionThreshold()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer);
+ return buffer[0];
+}
+/** Set zero motion detection event acceleration threshold.
+ * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg)
+ * @see getZeroMotionDetectionThreshold()
+ * @see MPU6050_RA_ZRMOT_THR
+ */
+void MPU6050::setZeroMotionDetectionThreshold(uint8_t threshold)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold);
+}
+
+// ZRMOT_DUR register
+
+/** Get zero motion detection event duration threshold.
+ * This register configures the duration counter threshold for Zero Motion
+ * interrupt generation. The duration counter ticks at 16 Hz, therefore
+ * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter
+ * increments while the absolute value of the accelerometer measurements are
+ * each less than the detection threshold (Register 33). The Zero Motion
+ * interrupt is triggered when the Zero Motion duration counter reaches the time
+ * count specified in this register.
+ *
+ * For more details on the Zero Motion detection interrupt, see Section 8.4 of
+ * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56
+ * and 58 of this document.
+ *
+ * @return Current zero motion detection duration threshold value (LSB = 64ms)
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+uint8_t MPU6050::getZeroMotionDetectionDuration()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer);
+ return buffer[0];
+}
+/** Set zero motion detection event duration threshold.
+ * @param duration New zero motion detection duration threshold value (LSB = 1ms)
+ * @see getZeroMotionDetectionDuration()
+ * @see MPU6050_RA_ZRMOT_DUR
+ */
+void MPU6050::setZeroMotionDetectionDuration(uint8_t duration)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration);
+}
+
+// FIFO_EN register
+
+/** Get temperature FIFO enabled value.
+ * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and
+ * 66) to be written into the FIFO buffer.
+ * @return Current temperature FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getTempFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set temperature FIFO enabled value.
+ * @param enabled New temperature FIFO enabled value
+ * @see getTempFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setTempFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope X-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and
+ * 68) to be written into the FIFO buffer.
+ * @return Current gyroscope X-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getXGyroFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set gyroscope X-axis FIFO enabled value.
+ * @param enabled New gyroscope X-axis FIFO enabled value
+ * @see getXGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setXGyroFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Y-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and
+ * 70) to be written into the FIFO buffer.
+ * @return Current gyroscope Y-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getYGyroFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set gyroscope Y-axis FIFO enabled value.
+ * @param enabled New gyroscope Y-axis FIFO enabled value
+ * @see getYGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setYGyroFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled);
+}
+/** Get gyroscope Z-axis FIFO enabled value.
+ * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and
+ * 72) to be written into the FIFO buffer.
+ * @return Current gyroscope Z-axis FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getZGyroFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set gyroscope Z-axis FIFO enabled value.
+ * @param enabled New gyroscope Z-axis FIFO enabled value
+ * @see getZGyroFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setZGyroFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled);
+}
+/** Get accelerometer FIFO enabled value.
+ * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H,
+ * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be
+ * written into the FIFO buffer.
+ * @return Current accelerometer FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getAccelFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set accelerometer FIFO enabled value.
+ * @param enabled New accelerometer FIFO enabled value
+ * @see getAccelFIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setAccelFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 2 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 2 to be written into the FIFO buffer.
+ * @return Current Slave 2 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave2FIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set Slave 2 FIFO enabled value.
+ * @param enabled New Slave 2 FIFO enabled value
+ * @see getSlave2FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave2FIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 1 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 1 to be written into the FIFO buffer.
+ * @return Current Slave 1 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave1FIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set Slave 1 FIFO enabled value.
+ * @param enabled New Slave 1 FIFO enabled value
+ * @see getSlave1FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave1FIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled);
+}
+/** Get Slave 0 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 0 to be written into the FIFO buffer.
+ * @return Current Slave 0 FIFO enabled value
+ * @see MPU6050_RA_FIFO_EN
+ */
+bool MPU6050::getSlave0FIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set Slave 0 FIFO enabled value.
+ * @param enabled New Slave 0 FIFO enabled value
+ * @see getSlave0FIFOEnabled()
+ * @see MPU6050_RA_FIFO_EN
+ */
+void MPU6050::setSlave0FIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled);
+}
+
+// I2C_MST_CTRL register
+
+/** Get multi-master enabled value.
+ * Multi-master capability allows multiple I2C masters to operate on the same
+ * bus. In circuits where multi-master capability is required, set MULT_MST_EN
+ * to 1. This will increase current drawn by approximately 30uA.
+ *
+ * In circuits where multi-master capability is required, the state of the I2C
+ * bus must always be monitored by each separate I2C Master. Before an I2C
+ * Master can assume arbitration of the bus, it must first confirm that no other
+ * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the
+ * MPU-60X0's bus arbitration detection logic is turned on, enabling it to
+ * detect when the bus is available.
+ *
+ * @return Current multi-master enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getMultiMasterEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set multi-master enabled value.
+ * @param enabled New multi-master enabled value
+ * @see getMultiMasterEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setMultiMasterEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled);
+}
+/** Get wait-for-external-sensor-data enabled value.
+ * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be
+ * delayed until External Sensor data from the Slave Devices are loaded into the
+ * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor
+ * data (i.e. from gyro and accel) and external sensor data have been loaded to
+ * their respective data registers (i.e. the data is synced) when the Data Ready
+ * interrupt is triggered.
+ *
+ * @return Current wait-for-external-sensor-data enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getWaitForExternalSensorEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer);
+ return buffer[0];
+}
+/** Set wait-for-external-sensor-data enabled value.
+ * @param enabled New wait-for-external-sensor-data enabled value
+ * @see getWaitForExternalSensorEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setWaitForExternalSensorEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled);
+}
+/** Get Slave 3 FIFO enabled value.
+ * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96)
+ * associated with Slave 3 to be written into the FIFO buffer.
+ * @return Current Slave 3 FIFO enabled value
+ * @see MPU6050_RA_MST_CTRL
+ */
+bool MPU6050::getSlave3FIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set Slave 3 FIFO enabled value.
+ * @param enabled New Slave 3 FIFO enabled value
+ * @see getSlave3FIFOEnabled()
+ * @see MPU6050_RA_MST_CTRL
+ */
+void MPU6050::setSlave3FIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled);
+}
+/** Get slave read/write transition enabled value.
+ * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave
+ * read to the next slave read. If the bit equals 0, there will be a restart
+ * between reads. If the bit equals 1, there will be a stop followed by a start
+ * of the following read. When a write transaction follows a read transaction,
+ * the stop followed by a start of the successive write will be always used.
+ *
+ * @return Current slave read/write transition enabled value
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+bool MPU6050::getSlaveReadWriteTransitionEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer);
+ return buffer[0];
+}
+/** Set slave read/write transition enabled value.
+ * @param enabled New slave read/write transition enabled value
+ * @see getSlaveReadWriteTransitionEnabled()
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setSlaveReadWriteTransitionEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled);
+}
+/** Get I2C master clock speed.
+ * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the
+ * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to
+ * the following table:
+ *
+ * <pre>
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0 | 348kHz | 23
+ * 1 | 333kHz | 24
+ * 2 | 320kHz | 25
+ * 3 | 308kHz | 26
+ * 4 | 296kHz | 27
+ * 5 | 286kHz | 28
+ * 6 | 276kHz | 29
+ * 7 | 267kHz | 30
+ * 8 | 258kHz | 31
+ * 9 | 500kHz | 16
+ * 10 | 471kHz | 17
+ * 11 | 444kHz | 18
+ * 12 | 421kHz | 19
+ * 13 | 400kHz | 20
+ * 14 | 381kHz | 21
+ * 15 | 364kHz | 22
+ * </pre>
+ *
+ * @return Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+uint8_t MPU6050::getMasterClockSpeed()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set I2C master clock speed.
+ * @reparam speed Current I2C master clock speed
+ * @see MPU6050_RA_I2C_MST_CTRL
+ */
+void MPU6050::setMasterClockSpeed(uint8_t speed)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed);
+}
+
+// I2C_SLV* registers (Slave 0-3)
+
+/** Get the I2C address of the specified slave (0-3).
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * In read mode, the result of the read is placed in the lowest available
+ * EXT_SENS_DATA register. For further information regarding the allocation of
+ * read results, please refer to the EXT_SENS_DATA register description
+ * (Registers 73 - 96).
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions (getSlave4* and setSlave4*).
+ *
+ * I2C data transactions are performed at the Sample Rate, as defined in
+ * Register 25. The user is responsible for ensuring that I2C data transactions
+ * to and from each enabled Slave can be completed within a single period of the
+ * Sample Rate.
+ *
+ * The I2C slave access rate can be reduced relative to the Sample Rate. This
+ * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a
+ * slave's access rate is reduced relative to the Sample Rate is determined by
+ * I2C_MST_DELAY_CTRL (Register 103).
+ *
+ * The processing order for the slaves is fixed. The sequence followed for
+ * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a
+ * particular Slave is disabled it will be skipped.
+ *
+ * Each slave can either be accessed at the sample rate or at a reduced sample
+ * rate. In a case where some slaves are accessed at the Sample Rate and some
+ * slaves are accessed at the reduced rate, the sequence of accessing the slaves
+ * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will
+ * be skipped if their access rate dictates that they should not be accessed
+ * during that particular cycle. For further information regarding the reduced
+ * access rate, please refer to Register 52. Whether a slave is accessed at the
+ * Sample Rate or at the reduced rate is determined by the Delay Enable bits in
+ * Register 103.
+ *
+ * @param num Slave number (0-3)
+ * @return Current address for specified slave
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+uint8_t MPU6050::getSlaveAddress(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer);
+ return buffer[0];
+}
+/** Set the I2C address of the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param address New address for specified slave
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV0_ADDR
+ */
+void MPU6050::setSlaveAddress(uint8_t num, uint8_t address)
+{
+ if (num > 3) return;
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address);
+}
+/** Get the active internal register for the specified slave (0-3).
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * The MPU-6050 supports a total of five slaves, but Slave 4 has unique
+ * characteristics, and so it has its own functions.
+ *
+ * @param num Slave number (0-3)
+ * @return Current active register for specified slave
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+uint8_t MPU6050::getSlaveRegister(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer);
+ return buffer[0];
+}
+/** Set the active internal register for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param reg New active register for specified slave
+ * @see getSlaveRegister()
+ * @see MPU6050_RA_I2C_SLV0_REG
+ */
+void MPU6050::setSlaveRegister(uint8_t num, uint8_t reg)
+{
+ if (num > 3) return;
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg);
+}
+/** Get the enabled value for the specified slave (0-3).
+ * When set to 1, this bit enables Slave 0 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 0 from data transfer operations.
+ * @param num Slave number (0-3)
+ * @return Current enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveEnabled(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set the enabled value for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New enabled value for specified slave
+ * @see getSlaveEnabled()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveEnabled(uint8_t num, bool enabled)
+{
+ if (num > 3) return;
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled);
+}
+/** Get word pair byte-swapping enabled for the specified slave (0-3).
+ * When set to 1, this bit enables byte swapping. When byte swapping is enabled,
+ * the high and low bytes of a word pair are swapped. Please refer to
+ * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0,
+ * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA
+ * registers in the order they were transferred.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair byte-swapping enabled value for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWordByteSwap(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer);
+ return buffer[0];
+}
+/** Set word pair byte-swapping enabled for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair byte-swapping enabled value for specified slave
+ * @see getSlaveWordByteSwap()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWordByteSwap(uint8_t num, bool enabled)
+{
+ if (num > 3) return;
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled);
+}
+/** Get write mode for the specified slave (0-3).
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @param num Slave number (0-3)
+ * @return Current write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWriteMode(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer);
+ return buffer[0];
+}
+/** Set write mode for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param mode New write mode for specified slave (0 = register address + data, 1 = data only)
+ * @see getSlaveWriteMode()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWriteMode(uint8_t num, bool mode)
+{
+ if (num > 3) return;
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode);
+}
+/** Get word pair grouping order offset for the specified slave (0-3).
+ * This sets specifies the grouping order of word pairs received from registers.
+ * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even,
+ * then odd register addresses) are paired to form a word. When set to 1, bytes
+ * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even
+ * register addresses) are paired to form a word.
+ *
+ * @param num Slave number (0-3)
+ * @return Current word pair grouping order offset for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+bool MPU6050::getSlaveWordGroupOffset(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer);
+ return buffer[0];
+}
+/** Set word pair grouping order offset for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param enabled New word pair grouping order offset for specified slave
+ * @see getSlaveWordGroupOffset()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveWordGroupOffset(uint8_t num, bool enabled)
+{
+ if (num > 3) return;
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled);
+}
+/** Get number of bytes to read for the specified slave (0-3).
+ * Specifies the number of bytes transferred to and from Slave 0. Clearing this
+ * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN.
+ * @param num Slave number (0-3)
+ * @return Number of bytes to read for specified slave
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+uint8_t MPU6050::getSlaveDataLength(uint8_t num)
+{
+ if (num > 3) return 0;
+ i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set number of bytes to read for the specified slave (0-3).
+ * @param num Slave number (0-3)
+ * @param length Number of bytes to read for specified slave
+ * @see getSlaveDataLength()
+ * @see MPU6050_RA_I2C_SLV0_CTRL
+ */
+void MPU6050::setSlaveDataLength(uint8_t num, uint8_t length)
+{
+ if (num > 3) return;
+ i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length);
+}
+
+// I2C_SLV* registers (Slave 4)
+
+/** Get the I2C address of Slave 4.
+ * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read
+ * operation, and if it is cleared, then it's a write operation. The remaining
+ * bits (6-0) are the 7-bit device address of the slave device.
+ *
+ * @return Current address for Slave 4
+ * @see getSlaveAddress()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+uint8_t MPU6050::getSlave4Address()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer);
+ return buffer[0];
+}
+/** Set the I2C address of Slave 4.
+ * @param address New address for Slave 4
+ * @see getSlave4Address()
+ * @see MPU6050_RA_I2C_SLV4_ADDR
+ */
+void MPU6050::setSlave4Address(uint8_t address)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address);
+}
+/** Get the active internal register for the Slave 4.
+ * Read/write operations for this slave will be done to whatever internal
+ * register address is stored in this MPU register.
+ *
+ * @return Current active register for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+uint8_t MPU6050::getSlave4Register()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer);
+ return buffer[0];
+}
+/** Set the active internal register for Slave 4.
+ * @param reg New active register for Slave 4
+ * @see getSlave4Register()
+ * @see MPU6050_RA_I2C_SLV4_REG
+ */
+void MPU6050::setSlave4Register(uint8_t reg)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg);
+}
+/** Set new byte to write to Slave 4.
+ * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW
+ * is set 1 (set to read), this register has no effect.
+ * @param data New byte to write to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DO
+ */
+void MPU6050::setSlave4OutputByte(uint8_t data)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data);
+}
+/** Get the enabled value for the Slave 4.
+ * When set to 1, this bit enables Slave 4 for data transfer operations. When
+ * cleared to 0, this bit disables Slave 4 from data transfer operations.
+ * @return Current enabled value for Slave 4
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4Enabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set the enabled value for Slave 4.
+ * @param enabled New enabled value for Slave 4
+ * @see getSlave4Enabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4Enabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled);
+}
+/** Get the enabled value for Slave 4 transaction interrupts.
+ * When set to 1, this bit enables the generation of an interrupt signal upon
+ * completion of a Slave 4 transaction. When cleared to 0, this bit disables the
+ * generation of an interrupt signal upon completion of a Slave 4 transaction.
+ * The interrupt status can be observed in Register 54.
+ *
+ * @return Current enabled value for Slave 4 transaction interrupts.
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4InterruptEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set the enabled value for Slave 4 transaction interrupts.
+ * @param enabled New enabled value for Slave 4 transaction interrupts.
+ * @see getSlave4InterruptEnabled()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4InterruptEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled);
+}
+/** Get write mode for Slave 4.
+ * When set to 1, the transaction will read or write data only. When cleared to
+ * 0, the transaction will write a register address prior to reading or writing
+ * data. This should equal 0 when specifying the register address within the
+ * Slave device to/from which the ensuing data transaction will take place.
+ *
+ * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+bool MPU6050::getSlave4WriteMode()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer);
+ return buffer[0];
+}
+/** Set write mode for the Slave 4.
+ * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only)
+ * @see getSlave4WriteMode()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4WriteMode(bool mode)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode);
+}
+/** Get Slave 4 master delay value.
+ * This configures the reduced access rate of I2C slaves relative to the Sample
+ * Rate. When a slave's access rate is decreased relative to the Sample Rate,
+ * the slave is accessed every:
+ *
+ * 1 / (1 + I2C_MST_DLY) samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and
+ * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to
+ * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For
+ * further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @return Current Slave 4 master delay value
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+uint8_t MPU6050::getSlave4MasterDelay()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set Slave 4 master delay value.
+ * @param delay New Slave 4 master delay value
+ * @see getSlave4MasterDelay()
+ * @see MPU6050_RA_I2C_SLV4_CTRL
+ */
+void MPU6050::setSlave4MasterDelay(uint8_t delay)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay);
+}
+/** Get last available byte read from Slave 4.
+ * This register stores the data read from Slave 4. This field is populated
+ * after a read transaction.
+ * @return Last available byte read from to Slave 4
+ * @see MPU6050_RA_I2C_SLV4_DI
+ */
+uint8_t MPU6050::getSlate4InputByte()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer);
+ return buffer[0];
+}
+
+// I2C_MST_STATUS register
+
+/** Get FSYNC interrupt status.
+ * This bit reflects the status of the FSYNC interrupt from an external device
+ * into the MPU-60X0. This is used as a way to pass an external interrupt
+ * through the MPU-60X0 to the host application processor. When set to 1, this
+ * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG
+ * (Register 55).
+ * @return FSYNC interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getPassthroughStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 4 transaction done status.
+ * Automatically sets to 1 when a Slave 4 transaction has completed. This
+ * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register
+ * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the
+ * I2C_SLV4_CTRL register (Register 52).
+ * @return Slave 4 transaction done status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave4IsDone()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer);
+ return buffer[0];
+}
+/** Get master arbitration lost status.
+ * This bit automatically sets to 1 when the I2C Master has lost arbitration of
+ * the auxiliary I2C bus (an error condition). This triggers an interrupt if the
+ * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Master arbitration lost status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getLostArbitration()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 4 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 4 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave4Nack()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 3 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 3 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave3Nack()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 2 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 2 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave2Nack()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 1 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 1 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave1Nack()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer);
+ return buffer[0];
+}
+/** Get Slave 0 NACK status.
+ * This bit automatically sets to 1 when the I2C Master receives a NACK in a
+ * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN
+ * bit in the INT_ENABLE register (Register 56) is asserted.
+ * @return Slave 0 NACK interrupt status
+ * @see MPU6050_RA_I2C_MST_STATUS
+ */
+bool MPU6050::getSlave0Nack()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer);
+ return buffer[0];
+}
+
+// INT_PIN_CFG register
+
+/** Get interrupt logic level mode.
+ * Will be set 0 for active-high, 1 for active-low.
+ * @return Current interrupt mode (0=active-high, 1=active-low)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+bool MPU6050::getInterruptMode()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer);
+ return buffer[0];
+}
+/** Set interrupt logic level mode.
+ * @param mode New interrupt mode (0=active-high, 1=active-low)
+ * @see getInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_LEVEL_BIT
+ */
+void MPU6050::setInterruptMode(bool mode)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode);
+}
+/** Get interrupt drive mode.
+ * Will be set 0 for push-pull, 1 for open-drain.
+ * @return Current interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+bool MPU6050::getInterruptDrive()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer);
+ return buffer[0];
+}
+/** Set interrupt drive mode.
+ * @param drive New interrupt drive mode (0=push-pull, 1=open-drain)
+ * @see getInterruptDrive()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_OPEN_BIT
+ */
+void MPU6050::setInterruptDrive(bool drive)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive);
+}
+/** Get interrupt latch mode.
+ * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared.
+ * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+bool MPU6050::getInterruptLatch()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set interrupt latch mode.
+ * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared)
+ * @see getInterruptLatch()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_LATCH_INT_EN_BIT
+ */
+void MPU6050::setInterruptLatch(bool latch)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch);
+}
+/** Get interrupt latch clear mode.
+ * Will be set 0 for status-read-only, 1 for any-register-read.
+ * @return Current latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+bool MPU6050::getInterruptLatchClear()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer);
+ return buffer[0];
+}
+/** Set interrupt latch clear mode.
+ * @param clear New latch clear mode (0=status-read-only, 1=any-register-read)
+ * @see getInterruptLatchClear()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT
+ */
+void MPU6050::setInterruptLatchClear(bool clear)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear);
+}
+/** Get FSYNC interrupt logic level mode.
+ * @return Current FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+bool MPU6050::getFSyncInterruptLevel()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer);
+ return buffer[0];
+}
+/** Set FSYNC interrupt logic level mode.
+ * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low)
+ * @see getFSyncInterruptMode()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT
+ */
+void MPU6050::setFSyncInterruptLevel(bool level)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level);
+}
+/** Get FSYNC pin interrupt enabled setting.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled setting
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+bool MPU6050::getFSyncInterruptEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set FSYNC pin interrupt enabled setting.
+ * @param enabled New FSYNC pin interrupt enabled setting
+ * @see getFSyncInterruptEnabled()
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT
+ */
+void MPU6050::setFSyncInterruptEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled);
+}
+/** Get I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @return Current I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+bool MPU6050::getI2CBypassEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set I2C bypass enabled status.
+ * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to
+ * 0, the host application processor will be able to directly access the
+ * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host
+ * application processor will not be able to directly access the auxiliary I2C
+ * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106
+ * bit[5]).
+ * @param enabled New I2C bypass enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT
+ */
+void MPU6050::setI2CBypassEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled);
+}
+/** Get reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @return Current reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+bool MPU6050::getClockOutputEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set reference clock output enabled status.
+ * When this bit is equal to 1, a reference clock output is provided at the
+ * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For
+ * further information regarding CLKOUT, please refer to the MPU-60X0 Product
+ * Specification document.
+ * @param enabled New reference clock output enabled status
+ * @see MPU6050_RA_INT_PIN_CFG
+ * @see MPU6050_INTCFG_CLKOUT_EN_BIT
+ */
+void MPU6050::setClockOutputEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled);
+}
+
+// INT_ENABLE register
+
+/** Get full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit will be
+ * set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+uint8_t MPU6050::getIntEnabled()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer);
+ return buffer[0];
+}
+/** Set full interrupt enabled status.
+ * Full register byte for all interrupts, for quick reading. Each bit should be
+ * set 0 for disabled, 1 for enabled.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050::setIntEnabled(uint8_t enabled)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled);
+}
+/** Get Free Fall interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+bool MPU6050::getIntFreefallEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer);
+ return buffer[0];
+}
+/** Set Free Fall interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFreefallEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FF_BIT
+ **/
+void MPU6050::setIntFreefallEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled);
+}
+/** Get Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+bool MPU6050::getIntMotionEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer);
+ return buffer[0];
+}
+/** Set Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ **/
+void MPU6050::setIntMotionEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled);
+}
+/** Get Zero Motion Detection interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+bool MPU6050::getIntZeroMotionEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+ return buffer[0];
+}
+/** Set Zero Motion Detection interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntZeroMotionEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ **/
+void MPU6050::setIntZeroMotionEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled);
+}
+/** Get FIFO Buffer Overflow interrupt enabled status.
+ * Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+bool MPU6050::getIntFIFOBufferOverflowEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+ return buffer[0];
+}
+/** Set FIFO Buffer Overflow interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntFIFOBufferOverflowEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ **/
+void MPU6050::setIntFIFOBufferOverflowEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled);
+}
+/** Get I2C Master interrupt enabled status.
+ * This enables any of the I2C Master interrupt sources to generate an
+ * interrupt. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+bool MPU6050::getIntI2CMasterEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+ return buffer[0];
+}
+/** Set I2C Master interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntI2CMasterEnabled()
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ **/
+void MPU6050::setIntI2CMasterEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled);
+}
+/** Get Data Ready interrupt enabled setting.
+ * This event occurs each time a write operation to all of the sensor registers
+ * has been completed. Will be set 0 for disabled, 1 for enabled.
+ * @return Current interrupt enabled status
+ * @see MPU6050_RA_INT_ENABLE
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050::getIntDataReadyEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+ return buffer[0];
+}
+/** Set Data Ready interrupt enabled status.
+ * @param enabled New interrupt enabled status
+ * @see getIntDataReadyEnabled()
+ * @see MPU6050_RA_INT_CFG
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+void MPU6050::setIntDataReadyEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled);
+}
+
+// INT_STATUS register
+
+/** Get full set of interrupt status bits.
+ * These bits clear to 0 after the register has been read. Very useful
+ * for getting multiple INT statuses, since each single bit read clears
+ * all of them because it has to read the whole byte.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ */
+uint8_t MPU6050::getIntStatus()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_INT_STATUS, buffer);
+ return buffer[0];
+}
+/** Get Free Fall interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FF_BIT
+ */
+bool MPU6050::getIntFreefallStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer);
+ return buffer[0];
+}
+/** Get Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Motion Detection interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_MOT_BIT
+ */
+bool MPU6050::getIntMotionStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer);
+ return buffer[0];
+}
+/** Get Zero Motion Detection interrupt status.
+ * This bit automatically sets to 1 when a Zero Motion Detection interrupt has
+ * been generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_ZMOT_BIT
+ */
+bool MPU6050::getIntZeroMotionStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer);
+ return buffer[0];
+}
+/** Get FIFO Buffer Overflow interrupt status.
+ * This bit automatically sets to 1 when a Free Fall interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT
+ */
+bool MPU6050::getIntFIFOBufferOverflowStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer);
+ return buffer[0];
+}
+/** Get I2C Master interrupt status.
+ * This bit automatically sets to 1 when an I2C Master interrupt has been
+ * generated. For a list of I2C Master interrupts, please refer to Register 54.
+ * The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT
+ */
+bool MPU6050::getIntI2CMasterStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer);
+ return buffer[0];
+}
+/** Get Data Ready interrupt status.
+ * This bit automatically sets to 1 when a Data Ready interrupt has been
+ * generated. The bit clears to 0 after the register has been read.
+ * @return Current interrupt status
+ * @see MPU6050_RA_INT_STATUS
+ * @see MPU6050_INTERRUPT_DATA_RDY_BIT
+ */
+bool MPU6050::getIntDataReadyStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer);
+ return buffer[0];
+}
+
+// ACCEL_*OUT_* registers
+
+/** Get raw 9-axis motion sensor readings (accel/gyro/compass).
+ * FUNCTION NOT FULLY IMPLEMENTED YET.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @param mx 16-bit signed integer container for magnetometer X-axis value
+ * @param my 16-bit signed integer container for magnetometer Y-axis value
+ * @param mz 16-bit signed integer container for magnetometer Z-axis value
+ * @see getMotion6()
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz)
+{
+ getMotion6(ax, ay, az, gx, gy, gz);
+
+ // magnetometer reading
+ i2Cdev.writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer
+ wait_ms(10); // necessary wait >=6ms
+ i2Cdev.writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); // enable the magnetometer
+ wait_ms(10); // necessary wait >=6ms
+ i2Cdev.readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer);
+ *mx = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *my = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *mz = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get raw 6-axis motion sensor readings (accel/gyro).
+ * Retrieves all currently available motion sensor values.
+ * @param ax 16-bit signed integer container for accelerometer X-axis value
+ * @param ay 16-bit signed integer container for accelerometer Y-axis value
+ * @param az 16-bit signed integer container for accelerometer Z-axis value
+ * @param gx 16-bit signed integer container for gyroscope X-axis value
+ * @param gy 16-bit signed integer container for gyroscope Y-axis value
+ * @param gz 16-bit signed integer container for gyroscope Z-axis value
+ * @see getAcceleration()
+ * @see getRotation()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+void MPU6050::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer);
+ *ax = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *ay = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *az = (((int16_t)buffer[4]) << 8) | buffer[5];
+ *gx = (((int16_t)buffer[8]) << 8) | buffer[9];
+ *gy = (((int16_t)buffer[10]) << 8) | buffer[11];
+ *gz = (((int16_t)buffer[12]) << 8) | buffer[13];
+}
+/** Get 3-axis accelerometer readings.
+ * These registers store the most recent accelerometer measurements.
+ * Accelerometer measurements are written to these registers at the Sample Rate
+ * as defined in Register 25.
+ *
+ * The accelerometer measurement registers, along with the temperature
+ * measurement registers, gyroscope measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ *
+ * The data within the accelerometer sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS
+ * (Register 28). For each full scale setting, the accelerometers' sensitivity
+ * per LSB in ACCEL_xOUT is shown in the table below:
+ *
+ * <pre>
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0 | +/- 2g | 8192 LSB/mg
+ * 1 | +/- 4g | 4096 LSB/mg
+ * 2 | +/- 8g | 2048 LSB/mg
+ * 3 | +/- 16g | 1024 LSB/mg
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis acceleration
+ * @param y 16-bit signed integer container for Y-axis acceleration
+ * @param z 16-bit signed integer container for Z-axis acceleration
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050::getAcceleration(int16_t* x, int16_t* y, int16_t* z)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer);
+ *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis accelerometer reading.
+ * @return X-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_XOUT_H
+ */
+int16_t MPU6050::getAccelerationX()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis accelerometer reading.
+ * @return Y-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_YOUT_H
+ */
+int16_t MPU6050::getAccelerationY()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis accelerometer reading.
+ * @return Z-axis acceleration measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_ACCEL_ZOUT_H
+ */
+int16_t MPU6050::getAccelerationZ()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// TEMP_OUT_* registers
+
+/** Get current internal temperature.
+ * @return Temperature reading in 16-bit 2's complement format
+ * @see MPU6050_RA_TEMP_OUT_H
+ */
+int16_t MPU6050::getTemperature()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// GYRO_*OUT_* registers
+
+/** Get 3-axis gyroscope readings.
+ * These gyroscope measurement registers, along with the accelerometer
+ * measurement registers, temperature measurement registers, and external sensor
+ * data registers, are composed of two sets of registers: an internal register
+ * set and a user-facing read register set.
+ * The data within the gyroscope sensors' internal register set is always
+ * updated at the Sample Rate. Meanwhile, the user-facing read register set
+ * duplicates the internal register set's data values whenever the serial
+ * interface is idle. This guarantees that a burst read of sensor registers will
+ * read measurements from the same sampling instant. Note that if burst reads
+ * are not used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL
+ * (Register 27). For each full scale setting, the gyroscopes' sensitivity per
+ * LSB in GYRO_xOUT is shown in the table below:
+ *
+ * <pre>
+ * FS_SEL | Full Scale Range | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0 | +/- 250 degrees/s | 131 LSB/deg/s
+ * 1 | +/- 500 degrees/s | 65.5 LSB/deg/s
+ * 2 | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3 | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * </pre>
+ *
+ * @param x 16-bit signed integer container for X-axis rotation
+ * @param y 16-bit signed integer container for Y-axis rotation
+ * @param z 16-bit signed integer container for Z-axis rotation
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+void MPU6050::getRotation(int16_t* x, int16_t* y, int16_t* z)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer);
+ *x = (((int16_t)buffer[0]) << 8) | buffer[1];
+ *y = (((int16_t)buffer[2]) << 8) | buffer[3];
+ *z = (((int16_t)buffer[4]) << 8) | buffer[5];
+}
+/** Get X-axis gyroscope reading.
+ * @return X-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_XOUT_H
+ */
+int16_t MPU6050::getRotationX()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Y-axis gyroscope reading.
+ * @return Y-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_YOUT_H
+ */
+int16_t MPU6050::getRotationY()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Get Z-axis gyroscope reading.
+ * @return Z-axis rotation measurement in 16-bit 2's complement format
+ * @see getMotion6()
+ * @see MPU6050_RA_GYRO_ZOUT_H
+ */
+int16_t MPU6050::getRotationZ()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// EXT_SENS_DATA_* registers
+
+/** Read single byte from external sensor data register.
+ * These registers store data read from external sensors by the Slave 0, 1, 2,
+ * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in
+ * I2C_SLV4_DI (Register 53).
+ *
+ * External sensor data is written to these registers at the Sample Rate as
+ * defined in Register 25. This access rate can be reduced by using the Slave
+ * Delay Enable registers (Register 103).
+ *
+ * External sensor data registers, along with the gyroscope measurement
+ * registers, accelerometer measurement registers, and temperature measurement
+ * registers, are composed of two sets of registers: an internal register set
+ * and a user-facing read register set.
+ *
+ * The data within the external sensors' internal register set is always updated
+ * at the Sample Rate (or the reduced access rate) whenever the serial interface
+ * is idle. This guarantees that a burst read of sensor registers will read
+ * measurements from the same sampling instant. Note that if burst reads are not
+ * used, the user is responsible for ensuring a set of single byte reads
+ * correspond to a single sampling instant by checking the Data Ready interrupt.
+ *
+ * Data is placed in these external sensor data registers according to
+ * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39,
+ * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from
+ * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as
+ * defined in Register 25) or delayed rate (if specified in Register 52 and
+ * 103). During each Sample cycle, slave reads are performed in order of Slave
+ * number. If all slaves are enabled with more than zero bytes to be read, the
+ * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3.
+ *
+ * Each enabled slave will have EXT_SENS_DATA registers associated with it by
+ * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from
+ * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may
+ * change the higher numbered slaves' associated registers. Furthermore, if
+ * fewer total bytes are being read from the external sensors as a result of
+ * such a change, then the data remaining in the registers which no longer have
+ * an associated slave device (i.e. high numbered registers) will remain in
+ * these previously allocated registers unless reset.
+ *
+ * If the sum of the read lengths of all SLVx transactions exceed the number of
+ * available EXT_SENS_DATA registers, the excess bytes will be dropped. There
+ * are 24 EXT_SENS_DATA registers and hence the total read lengths between all
+ * the slaves cannot be greater than 24 or some bytes will be lost.
+ *
+ * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further
+ * information regarding the characteristics of Slave 4, please refer to
+ * Registers 49 to 53.
+ *
+ * EXAMPLE:
+ * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and
+ * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that
+ * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00
+ * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05
+ * will be associated with Slave 1. If Slave 2 is enabled as well, registers
+ * starting from EXT_SENS_DATA_06 will be allocated to Slave 2.
+ *
+ * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then
+ * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3
+ * instead.
+ *
+ * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE:
+ * If a slave is disabled at any time, the space initially allocated to the
+ * slave in the EXT_SENS_DATA register, will remain associated with that slave.
+ * This is to avoid dynamic adjustment of the register allocation.
+ *
+ * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all
+ * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106).
+ *
+ * This above is also true if one of the slaves gets NACKed and stops
+ * functioning.
+ *
+ * @param position Starting position (0-23)
+ * @return Byte read from register
+ */
+uint8_t MPU6050::getExternalSensorByte(int position)
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer);
+ return buffer[0];
+}
+/** Read word (2 bytes) from external sensor data registers.
+ * @param position Starting position (0-21)
+ * @return Word read from register
+ * @see getExternalSensorByte()
+ */
+uint16_t MPU6050::getExternalSensorWord(int position)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer);
+ return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+/** Read double word (4 bytes) from external sensor data registers.
+ * @param position Starting position (0-20)
+ * @return Double word read from registers
+ * @see getExternalSensorByte()
+ */
+uint32_t MPU6050::getExternalSensorDWord(int position)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer);
+ return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3];
+}
+
+// MOT_DETECT_STATUS register
+
+/** Get X-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XNEG_BIT
+ */
+bool MPU6050::getXNegMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer);
+ return buffer[0];
+}
+/** Get X-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_XPOS_BIT
+ */
+bool MPU6050::getXPosMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer);
+ return buffer[0];
+}
+/** Get Y-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YNEG_BIT
+ */
+bool MPU6050::getYNegMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer);
+ return buffer[0];
+}
+/** Get Y-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_YPOS_BIT
+ */
+bool MPU6050::getYPosMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer);
+ return buffer[0];
+}
+/** Get Z-axis negative motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZNEG_BIT
+ */
+bool MPU6050::getZNegMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer);
+ return buffer[0];
+}
+/** Get Z-axis positive motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZPOS_BIT
+ */
+bool MPU6050::getZPosMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer);
+ return buffer[0];
+}
+/** Get zero motion detection interrupt status.
+ * @return Motion detection status
+ * @see MPU6050_RA_MOT_DETECT_STATUS
+ * @see MPU6050_MOTION_MOT_ZRMOT_BIT
+ */
+bool MPU6050::getZeroMotionDetected()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer);
+ return buffer[0];
+}
+
+// I2C_SLV*_DO register
+
+/** Write byte to Data Output container for specified slave.
+ * This register holds the output data written into Slave when Slave is set to
+ * write mode. For further information regarding Slave control, please
+ * refer to Registers 37 to 39 and immediately following.
+ * @param num Slave number (0-3)
+ * @param data Byte to write
+ * @see MPU6050_RA_I2C_SLV0_DO
+ */
+void MPU6050::setSlaveOutputByte(uint8_t num, uint8_t data)
+{
+ if (num > 3) return;
+ i2Cdev.writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data);
+}
+
+// I2C_MST_DELAY_CTRL register
+
+/** Get external data shadow delay enabled status.
+ * This register is used to specify the timing of external sensor data
+ * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external
+ * sensor data is delayed until all data has been received.
+ * @return Current external data shadow delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+bool MPU6050::getExternalShadowDelayEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer);
+ return buffer[0];
+}
+/** Set external data shadow delay enabled status.
+ * @param enabled New external data shadow delay enabled status.
+ * @see getExternalShadowDelayEnabled()
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT
+ */
+void MPU6050::setExternalShadowDelayEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled);
+}
+/** Get slave delay enabled status.
+ * When a particular slave delay is enabled, the rate of access for the that
+ * slave device is reduced. When a slave's access rate is decreased relative to
+ * the Sample Rate, the slave is accessed every:
+ *
+ * 1 / (1 + I2C_MST_DLY) Samples
+ *
+ * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25)
+ * and DLPF_CFG (register 26).
+ *
+ * For further information regarding I2C_MST_DLY, please refer to register 52.
+ * For further information regarding the Sample Rate, please refer to register 25.
+ *
+ * @param num Slave number (0-4)
+ * @return Current slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+bool MPU6050::getSlaveDelayEnabled(uint8_t num)
+{
+ // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc.
+ if (num > 4) return 0;
+ i2Cdev.readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer);
+ return buffer[0];
+}
+/** Set slave delay enabled status.
+ * @param num Slave number (0-4)
+ * @param enabled New slave delay enabled status.
+ * @see MPU6050_RA_I2C_MST_DELAY_CTRL
+ * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT
+ */
+void MPU6050::setSlaveDelayEnabled(uint8_t num, bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled);
+}
+
+// SIGNAL_PATH_RESET register
+
+/** Reset gyroscope signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_GYRO_RESET_BIT
+ */
+void MPU6050::resetGyroscopePath()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true);
+}
+/** Reset accelerometer signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_ACCEL_RESET_BIT
+ */
+void MPU6050::resetAccelerometerPath()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true);
+}
+/** Reset temperature sensor signal path.
+ * The reset will revert the signal path analog to digital converters and
+ * filters to their power up configurations.
+ * @see MPU6050_RA_SIGNAL_PATH_RESET
+ * @see MPU6050_PATHRESET_TEMP_RESET_BIT
+ */
+void MPU6050::resetTemperaturePath()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true);
+}
+
+// MOT_DETECT_CTRL register
+
+/** Get accelerometer power-on delay.
+ * The accelerometer data path provides samples to the sensor registers, Motion
+ * detection, Zero Motion detection, and Free Fall detection modules. The
+ * signal path contains filters which must be flushed on wake-up with new
+ * samples before the detection modules begin operations. The default wake-up
+ * delay, of 4ms can be lengthened by up to 3ms. This additional delay is
+ * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select
+ * any value above zero unless instructed otherwise by InvenSense. Please refer
+ * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for
+ * further information regarding the detection modules.
+ * @return Current accelerometer power-on delay
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+uint8_t MPU6050::getAccelerometerPowerOnDelay()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set accelerometer power-on delay.
+ * @param delay New accelerometer power-on delay (0-3)
+ * @see getAccelerometerPowerOnDelay()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT
+ */
+void MPU6050::setAccelerometerPowerOnDelay(uint8_t delay)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay);
+}
+/** Get Free Fall detection counter decrement configuration.
+ * Detection is registered by the Free Fall detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring FF_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0 | Reset
+ * 1 | 1
+ * 2 | 2
+ * 3 | 4
+ * </pre>
+ *
+ * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Free Fall detection,
+ * please refer to Registers 29 to 32.
+ *
+ * @return Current decrement configuration
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+uint8_t MPU6050::getFreefallDetectionCounterDecrement()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set Free Fall detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getFreefallDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_FF_COUNT_BIT
+ */
+void MPU6050::setFreefallDetectionCounterDecrement(uint8_t decrement)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement);
+}
+/** Get Motion detection counter decrement configuration.
+ * Detection is registered by the Motion detection module after accelerometer
+ * measurements meet their respective threshold conditions over a specified
+ * number of samples. When the threshold conditions are met, the corresponding
+ * detection counter increments by 1. The user may control the rate at which the
+ * detection counter decrements when the threshold condition is not met by
+ * configuring MOT_COUNT. The decrement rate can be set according to the
+ * following table:
+ *
+ * <pre>
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0 | Reset
+ * 1 | 1
+ * 2 | 2
+ * 3 | 4
+ * </pre>
+ *
+ * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will
+ * reset the counter to 0. For further information on Motion detection,
+ * please refer to Registers 29 to 32.
+ *
+ */
+uint8_t MPU6050::getMotionDetectionCounterDecrement()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set Motion detection counter decrement configuration.
+ * @param decrement New decrement configuration value
+ * @see getMotionDetectionCounterDecrement()
+ * @see MPU6050_RA_MOT_DETECT_CTRL
+ * @see MPU6050_DETECT_MOT_COUNT_BIT
+ */
+void MPU6050::setMotionDetectionCounterDecrement(uint8_t decrement)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement);
+}
+
+// USER_CTRL register
+
+/** Get FIFO enabled status.
+ * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer
+ * cannot be written to or read from while disabled. The FIFO buffer's state
+ * does not change unless the MPU-60X0 is power cycled.
+ * @return Current FIFO enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+bool MPU6050::getFIFOEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set FIFO enabled status.
+ * @param enabled New FIFO enabled status
+ * @see getFIFOEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_EN_BIT
+ */
+void MPU6050::setFIFOEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled);
+}
+/** Get I2C Master Mode enabled status.
+ * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the
+ * external sensor slave devices on the auxiliary I2C bus. When this bit is
+ * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically
+ * driven by the primary I2C bus (SDA and SCL). This is a precondition to
+ * enabling Bypass Mode. For further information regarding Bypass Mode, please
+ * refer to Register 55.
+ * @return Current I2C Master Mode enabled status
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+bool MPU6050::getI2CMasterModeEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer);
+ return buffer[0];
+}
+/** Set I2C Master Mode enabled status.
+ * @param enabled New I2C Master Mode enabled status
+ * @see getI2CMasterModeEnabled()
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_EN_BIT
+ */
+void MPU6050::setI2CMasterModeEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled);
+}
+/** Switch from I2C to SPI mode (MPU-6000 only)
+ * If this is set, the primary SPI interface will be enabled in place of the
+ * disabled primary I2C interface.
+ */
+void MPU6050::switchSPIEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled);
+}
+/** Reset the FIFO.
+ * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This
+ * bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_FIFO_RESET_BIT
+ */
+void MPU6050::resetFIFO()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true);
+}
+/** Reset the I2C Master.
+ * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0.
+ * This bit automatically clears to 0 after the reset has been triggered.
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT
+ */
+void MPU6050::resetI2CMaster()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true);
+}
+/** Reset all sensor registers and signal paths.
+ * When set to 1, this bit resets the signal paths for all sensors (gyroscopes,
+ * accelerometers, and temperature sensor). This operation will also clear the
+ * sensor registers. This bit automatically clears to 0 after the reset has been
+ * triggered.
+ *
+ * When resetting only the signal path (and not the sensor registers), please
+ * use Register 104, SIGNAL_PATH_RESET.
+ *
+ * @see MPU6050_RA_USER_CTRL
+ * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT
+ */
+void MPU6050::resetSensors()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true);
+}
+
+// PWR_MGMT_1 register
+
+/** Trigger a full device reset.
+ * A small delay of ~50ms may be desirable after triggering a reset.
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_DEVICE_RESET_BIT
+ */
+void MPU6050::reset()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true);
+}
+/** Get sleep mode status.
+ * Setting the SLEEP bit in the register puts the device into very low power
+ * sleep mode. In this mode, only the serial interface and internal registers
+ * remain active, allowing for a very low standby current. Clearing this bit
+ * puts the device back into normal mode. To save power, the individual standby
+ * selections for each of the gyros should be used if any gyro axis is not used
+ * by the application.
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+bool MPU6050::getSleepEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer);
+ return buffer[0];
+}
+/** Set sleep mode status.
+ * @param enabled New sleep mode enabled status
+ * @see getSleepEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_SLEEP_BIT
+ */
+void MPU6050::setSleepEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled);
+}
+/** Get wake cycle enabled status.
+ * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle
+ * between sleep mode and waking up to take a single sample of data from active
+ * sensors at a rate determined by LP_WAKE_CTRL (register 108).
+ * @return Current sleep mode enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+bool MPU6050::getWakeCycleEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer);
+ return buffer[0];
+}
+/** Set wake cycle enabled status.
+ * @param enabled New sleep mode enabled status
+ * @see getWakeCycleEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CYCLE_BIT
+ */
+void MPU6050::setWakeCycleEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled);
+}
+/** Get temperature sensor enabled status.
+ * Control the usage of the internal temperature sensor.
+ *
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @return Current temperature sensor enabled status
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+bool MPU6050::getTempSensorEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer);
+ return buffer[0] == 0; // 1 is actually disabled here
+}
+/** Set temperature sensor enabled status.
+ * Note: this register stores the *disabled* value, but for consistency with the
+ * rest of the code, the function is named and used with standard true/false
+ * values to indicate whether the sensor is enabled or disabled, respectively.
+ *
+ * @param enabled New temperature sensor enabled status
+ * @see getTempSensorEnabled()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_TEMP_DIS_BIT
+ */
+void MPU6050::setTempSensorEnabled(bool enabled)
+{
+ // 1 is actually disabled here
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled);
+}
+/** Get clock source setting.
+ * @return Current clock source setting
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+uint8_t MPU6050::getClockSource()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set clock source setting.
+ * An internal 8MHz oscillator, gyroscope based clock, or external sources can
+ * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator
+ * or an external source is chosen as the clock source, the MPU-60X0 can operate
+ * in low power modes with the gyroscopes disabled.
+ *
+ * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator.
+ * However, it is highly recommended that the device be configured to use one of
+ * the gyroscopes (or an external clock source) as the clock reference for
+ * improved stability. The clock source can be selected according to the following table:
+ *
+ * <pre>
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0 | Internal oscillator
+ * 1 | PLL with X Gyro reference
+ * 2 | PLL with Y Gyro reference
+ * 3 | PLL with Z Gyro reference
+ * 4 | PLL with external 32.768kHz reference
+ * 5 | PLL with external 19.2MHz reference
+ * 6 | Reserved
+ * 7 | Stops the clock and keeps the timing generator in reset
+ * </pre>
+ *
+ * @param source New clock source setting
+ * @see getClockSource()
+ * @see MPU6050_RA_PWR_MGMT_1
+ * @see MPU6050_PWR1_CLKSEL_BIT
+ * @see MPU6050_PWR1_CLKSEL_LENGTH
+ */
+void MPU6050::setClockSource(uint8_t source)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source);
+}
+
+// PWR_MGMT_2 register
+
+/** Get wake frequency in Accel-Only Low Power Mode.
+ * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting
+ * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode,
+ * the device will power off all devices except for the primary I2C interface,
+ * waking only the accelerometer at fixed intervals to take a single
+ * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL
+ * as shown below:
+ *
+ * <pre>
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0 | 1.25 Hz
+ * 1 | 2.5 Hz
+ * 2 | 5 Hz
+ * 3 | 10 Hz
+ * <pre>
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+uint8_t MPU6050::getWakeFrequency()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU6050_RA_PWR_MGMT_2
+ */
+void MPU6050::setWakeFrequency(uint8_t frequency)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+bool MPU6050::getStandbyXAccelEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer);
+ return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XA_BIT
+ */
+void MPU6050::setStandbyXAccelEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+bool MPU6050::getStandbyYAccelEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer);
+ return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YA_BIT
+ */
+void MPU6050::setStandbyYAccelEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+bool MPU6050::getStandbyZAccelEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer);
+ return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZA_BIT
+ */
+void MPU6050::setStandbyZAccelEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+bool MPU6050::getStandbyXGyroEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer);
+ return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_XG_BIT
+ */
+void MPU6050::setStandbyXGyroEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+bool MPU6050::getStandbyYGyroEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer);
+ return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_YG_BIT
+ */
+void MPU6050::setStandbyYGyroEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+bool MPU6050::getStandbyZGyroEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer);
+ return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU6050_RA_PWR_MGMT_2
+ * @see MPU6050_PWR2_STBY_ZG_BIT
+ */
+void MPU6050::setStandbyZGyroEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU6050::getFIFOCount()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer);
+ return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU6050::getFIFOByte()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer);
+ return buffer[0];
+}
+void MPU6050::getFIFOBytes(uint8_t *data, uint8_t length)
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6050::setFIFOByte(uint8_t data)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100, 0x34).
+ * @return Device ID (6 bits only! should be 0x34)
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+uint8_t MPU6050::getDeviceID()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer);
+ return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU6050_RA_WHO_AM_I
+ * @see MPU6050_WHO_AM_I_BIT
+ * @see MPU6050_WHO_AM_I_LENGTH
+ */
+void MPU6050::setDeviceID(uint8_t id)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU6050::getOTPBankValid()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer);
+ return buffer[0];
+}
+void MPU6050::setOTPBankValid(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU6050::getXGyroOffset()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+ return buffer[0];
+}
+void MPU6050::setXGyroOffset(int8_t offset)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6050::getYGyroOffset()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+ return buffer[0];
+}
+void MPU6050::setYGyroOffset(int8_t offset)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6050::getZGyroOffset()
+{
+ i2Cdev.readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer);
+ return buffer[0];
+}
+void MPU6050::setZGyroOffset(int8_t offset)
+{
+ i2Cdev.writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU6050::getXFineGain()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer);
+ return buffer[0];
+}
+void MPU6050::setXFineGain(int8_t gain)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6050::getYFineGain()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer);
+ return buffer[0];
+}
+void MPU6050::setYFineGain(int8_t gain)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6050::getZFineGain()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer);
+ return buffer[0];
+}
+void MPU6050::setZFineGain(int8_t gain)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6050::getXAccelOffset()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setXAccelOffset(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6050::getYAccelOffset()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setYAccelOffset(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6050::getZAccelOffset()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setZAccelOffset(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6050::getXGyroOffsetUser()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setXGyroOffsetUser(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6050::getYGyroOffsetUser()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setYGyroOffsetUser(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6050::getZGyroOffsetUser()
+{
+ i2Cdev.readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer);
+ return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU6050::setZGyroOffsetUser(int16_t offset)
+{
+ i2Cdev.writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6050::getIntPLLReadyEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+ return buffer[0];
+}
+void MPU6050::setIntPLLReadyEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU6050::getIntDMPEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+ return buffer[0];
+}
+void MPU6050::setIntDMPEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6050::getDMPInt5Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getDMPInt4Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getDMPInt3Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getDMPInt2Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getDMPInt1Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getDMPInt0Status()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer);
+ return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6050::getIntPLLReadyStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+ return buffer[0];
+}
+bool MPU6050::getIntDMPStatus()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer);
+ return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6050::getDMPEnabled()
+{
+ i2Cdev.readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer);
+ return buffer[0];
+}
+void MPU6050::setDMPEnabled(bool enabled)
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU6050::resetDMP()
+{
+ i2Cdev.writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU6050::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank)
+{
+ bank &= 0x1F;
+ if (userBank) bank |= 0x20;
+ if (prefetchEnabled) bank |= 0x40;
+ i2Cdev.writeByte(devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU6050::setMemoryStartAddress(uint8_t address)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6050::readMemoryByte()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_MEM_R_W, buffer);
+ return buffer[0];
+}
+void MPU6050::writeMemoryByte(uint8_t data)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void MPU6050::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address)
+{
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ uint8_t chunkSize;
+ for (uint16_t i = 0; i < dataSize;) {
+ // determine correct chunk size according to bank position and data size
+ chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+ // make sure we don't go past the data size
+ if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+ // make sure this chunk doesn't go past the bank boundary (256 bytes)
+ if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+ // read the chunk of data as specified
+ i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i);
+
+ // increase byte index by [chunkSize]
+ i += chunkSize;
+
+ // uint8_t automatically wraps to 0 at 256
+ address += chunkSize;
+
+ // if we aren't done, update bank (if necessary) and address
+ if (i < dataSize) {
+ if (address == 0) bank++;
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ }
+ }
+}
+bool MPU6050::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem)
+{
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ uint8_t chunkSize;
+ uint8_t *verifyBuffer = NULL;
+ uint8_t *progBuffer = NULL;
+ uint16_t i;
+ uint8_t j;
+ if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+ if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
+ for (i = 0; i < dataSize;) {
+ // determine correct chunk size according to bank position and data size
+ chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
+
+ // make sure we don't go past the data size
+ if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+ // make sure this chunk doesn't go past the bank boundary (256 bytes)
+ if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+ if (useProgMem) {
+ // write the chunk of data as specified
+ for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+ } else {
+ // write the chunk of data as specified
+ progBuffer = (uint8_t *)data + i;
+ }
+
+ i2Cdev.writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+ // verify data if needed
+ if (verify && verifyBuffer) {
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ i2Cdev.readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
+ if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+ /*Serial.print("Block write verification error, bank ");
+ Serial.print(bank, DEC);
+ Serial.print(", address ");
+ Serial.print(address, DEC);
+ Serial.print("!\nExpected:");
+ for (j = 0; j < chunkSize; j++) {
+ Serial.print(" 0x");
+ if (progBuffer[j] < 16) Serial.print("0");
+ Serial.print(progBuffer[j], HEX);
+ }
+ Serial.print("\nReceived:");
+ for (uint8_t j = 0; j < chunkSize; j++) {
+ Serial.print(" 0x");
+ if (verifyBuffer[i + j] < 16) Serial.print("0");
+ Serial.print(verifyBuffer[i + j], HEX);
+ }
+ Serial.print("\n");*/
+ free(verifyBuffer);
+ if (useProgMem) free(progBuffer);
+ return false; // uh oh.
+ }
+ }
+
+ // increase byte index by [chunkSize]
+ i += chunkSize;
+
+ // uint8_t automatically wraps to 0 at 256
+ address += chunkSize;
+
+ // if we aren't done, update bank (if necessary) and address
+ if (i < dataSize) {
+ if (address == 0) bank++;
+ setMemoryBank(bank);
+ setMemoryStartAddress(address);
+ }
+ }
+ if (verify) free(verifyBuffer);
+ if (useProgMem) free(progBuffer);
+ return true;
+}
+bool MPU6050::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify)
+{
+ return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6050::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem)
+{
+ uint8_t success, special;
+ uint8_t *progBuffer = NULL;
+ uint16_t i, j;
+ if (useProgMem) {
+ progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+ }
+
+ // config set data is a long string of blocks with the following structure:
+ // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+ uint8_t bank, offset, length;
+ for (i = 0; i < dataSize;) {
+ if (useProgMem) {
+ bank = pgm_read_byte(data + i++);
+ offset = pgm_read_byte(data + i++);
+ length = pgm_read_byte(data + i++);
+ } else {
+ bank = data[i++];
+ offset = data[i++];
+ length = data[i++];
+ }
+
+ // write data or perform special action
+ if (length > 0) {
+ // regular block of data to write
+ /*Serial.print("Writing config block to bank ");
+ Serial.print(bank);
+ Serial.print(", offset ");
+ Serial.print(offset);
+ Serial.print(", length=");
+ Serial.println(length);*/
+ if (useProgMem) {
+ if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+ for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+ } else {
+ progBuffer = (uint8_t *)data + i;
+ }
+ success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+ i += length;
+ } else {
+ // special instruction
+ // NOTE: this kind of behavior (what and when to do certain things)
+ // is totally undocumented. This code is in here based on observed
+ // behavior only, and exactly why (or even whether) it has to be here
+ // is anybody's guess for now.
+ if (useProgMem) {
+ special = pgm_read_byte(data + i++);
+ } else {
+ special = data[i++];
+ }
+ /*Serial.print("Special command code ");
+ Serial.print(special, HEX);
+ Serial.println(" found...");*/
+ if (special == 0x01) {
+ // enable DMP-related interrupts
+
+ //setIntZeroMotionEnabled(true);
+ //setIntFIFOBufferOverflowEnabled(true);
+ //setIntDMPEnabled(true);
+ i2Cdev.writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32); // single operation
+
+ success = true;
+ } else {
+ // unknown special command
+ success = false;
+ }
+ }
+
+ if (!success) {
+ if (useProgMem) free(progBuffer);
+ return false; // uh oh
+ }
+ }
+ if (useProgMem) free(progBuffer);
+ return true;
+}
+bool MPU6050::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize)
+{
+ return writeDMPConfigurationSet(data, dataSize, false);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU6050::getDMPConfig1()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer);
+ return buffer[0];
+}
+void MPU6050::setDMPConfig1(uint8_t config)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6050::getDMPConfig2()
+{
+ i2Cdev.readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer);
+ return buffer[0];
+}
+void MPU6050::setDMPConfig2(uint8_t config)
+{
+ i2Cdev.writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e MPU6050.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU6050.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,1006 @@
+//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>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_H_
+#define _MPU6050_H_
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+#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)
+#define MPU6050_DEFAULT_ADDRESS MPU6050_ADDRESS_AD0_HIGH
+
+#define MPU6050_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU6050_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
+#define MPU6050_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
+#define MPU6050_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
+#define MPU6050_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
+#define MPU6050_RA_XA_OFFS_L_TC 0x07
+#define MPU6050_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
+#define MPU6050_RA_YA_OFFS_L_TC 0x09
+#define MPU6050_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
+#define MPU6050_RA_ZA_OFFS_L_TC 0x0B
+#define MPU6050_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
+#define MPU6050_RA_XG_OFFS_USRL 0x14
+#define MPU6050_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
+#define MPU6050_RA_YG_OFFS_USRL 0x16
+#define MPU6050_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
+#define MPU6050_RA_ZG_OFFS_USRL 0x18
+#define MPU6050_RA_SMPLRT_DIV 0x19
+#define MPU6050_RA_CONFIG 0x1A
+#define MPU6050_RA_GYRO_CONFIG 0x1B
+#define MPU6050_RA_ACCEL_CONFIG 0x1C
+#define MPU6050_RA_FF_THR 0x1D
+#define MPU6050_RA_FF_DUR 0x1E
+#define MPU6050_RA_MOT_THR 0x1F
+#define MPU6050_RA_MOT_DUR 0x20
+#define MPU6050_RA_ZRMOT_THR 0x21
+#define MPU6050_RA_ZRMOT_DUR 0x22
+#define MPU6050_RA_FIFO_EN 0x23
+#define MPU6050_RA_I2C_MST_CTRL 0x24
+#define MPU6050_RA_I2C_SLV0_ADDR 0x25
+#define MPU6050_RA_I2C_SLV0_REG 0x26
+#define MPU6050_RA_I2C_SLV0_CTRL 0x27
+#define MPU6050_RA_I2C_SLV1_ADDR 0x28
+#define MPU6050_RA_I2C_SLV1_REG 0x29
+#define MPU6050_RA_I2C_SLV1_CTRL 0x2A
+#define MPU6050_RA_I2C_SLV2_ADDR 0x2B
+#define MPU6050_RA_I2C_SLV2_REG 0x2C
+#define MPU6050_RA_I2C_SLV2_CTRL 0x2D
+#define MPU6050_RA_I2C_SLV3_ADDR 0x2E
+#define MPU6050_RA_I2C_SLV3_REG 0x2F
+#define MPU6050_RA_I2C_SLV3_CTRL 0x30
+#define MPU6050_RA_I2C_SLV4_ADDR 0x31
+#define MPU6050_RA_I2C_SLV4_REG 0x32
+#define MPU6050_RA_I2C_SLV4_DO 0x33
+#define MPU6050_RA_I2C_SLV4_CTRL 0x34
+#define MPU6050_RA_I2C_SLV4_DI 0x35
+#define MPU6050_RA_I2C_MST_STATUS 0x36
+#define MPU6050_RA_INT_PIN_CFG 0x37
+#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
+#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
+#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
+#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
+#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
+#define MPU6050_RA_EXT_SENS_DATA_07 0x50
+#define MPU6050_RA_EXT_SENS_DATA_08 0x51
+#define MPU6050_RA_EXT_SENS_DATA_09 0x52
+#define MPU6050_RA_EXT_SENS_DATA_10 0x53
+#define MPU6050_RA_EXT_SENS_DATA_11 0x54
+#define MPU6050_RA_EXT_SENS_DATA_12 0x55
+#define MPU6050_RA_EXT_SENS_DATA_13 0x56
+#define MPU6050_RA_EXT_SENS_DATA_14 0x57
+#define MPU6050_RA_EXT_SENS_DATA_15 0x58
+#define MPU6050_RA_EXT_SENS_DATA_16 0x59
+#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
+#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
+#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
+#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
+#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
+#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
+#define MPU6050_RA_EXT_SENS_DATA_23 0x60
+#define MPU6050_RA_MOT_DETECT_STATUS 0x61
+#define MPU6050_RA_I2C_SLV0_DO 0x63
+#define MPU6050_RA_I2C_SLV1_DO 0x64
+#define MPU6050_RA_I2C_SLV2_DO 0x65
+#define MPU6050_RA_I2C_SLV3_DO 0x66
+#define MPU6050_RA_I2C_MST_DELAY_CTRL 0x67
+#define MPU6050_RA_SIGNAL_PATH_RESET 0x68
+#define MPU6050_RA_MOT_DETECT_CTRL 0x69
+#define MPU6050_RA_USER_CTRL 0x6A
+#define MPU6050_RA_PWR_MGMT_1 0x6B
+#define MPU6050_RA_PWR_MGMT_2 0x6C
+#define MPU6050_RA_BANK_SEL 0x6D
+#define MPU6050_RA_MEM_START_ADDR 0x6E
+#define MPU6050_RA_MEM_R_W 0x6F
+#define MPU6050_RA_DMP_CFG_1 0x70
+#define MPU6050_RA_DMP_CFG_2 0x71
+#define MPU6050_RA_FIFO_COUNTH 0x72
+#define MPU6050_RA_FIFO_COUNTL 0x73
+#define MPU6050_RA_FIFO_R_W 0x74
+#define MPU6050_RA_WHO_AM_I 0x75
+
+#define MPU6050_TC_PWR_MODE_BIT 7
+#define MPU6050_TC_OFFSET_BIT 6
+#define MPU6050_TC_OFFSET_LENGTH 6
+#define MPU6050_TC_OTP_BNK_VLD_BIT 0
+
+#define MPU6050_VDDIO_LEVEL_VLOGIC 0
+#define MPU6050_VDDIO_LEVEL_VDD 1
+
+#define MPU6050_CFG_EXT_SYNC_SET_BIT 5
+#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU6050_CFG_DLPF_CFG_BIT 2
+#define MPU6050_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU6050_EXT_SYNC_DISABLED 0x0
+#define MPU6050_EXT_SYNC_TEMP_OUT_L 0x1
+#define MPU6050_EXT_SYNC_GYRO_XOUT_L 0x2
+#define MPU6050_EXT_SYNC_GYRO_YOUT_L 0x3
+#define MPU6050_EXT_SYNC_GYRO_ZOUT_L 0x4
+#define MPU6050_EXT_SYNC_ACCEL_XOUT_L 0x5
+#define MPU6050_EXT_SYNC_ACCEL_YOUT_L 0x6
+#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L 0x7
+
+#define MPU6050_DLPF_BW_256 0x00
+#define MPU6050_DLPF_BW_188 0x01
+#define MPU6050_DLPF_BW_98 0x02
+#define MPU6050_DLPF_BW_42 0x03
+#define MPU6050_DLPF_BW_20 0x04
+#define MPU6050_DLPF_BW_10 0x05
+#define MPU6050_DLPF_BW_5 0x06
+
+#define MPU6050_GCONFIG_FS_SEL_BIT 4
+#define MPU6050_GCONFIG_FS_SEL_LENGTH 2
+
+#define MPU6050_GYRO_FS_250 0x00
+#define MPU6050_GYRO_FS_500 0x01
+#define MPU6050_GYRO_FS_1000 0x02
+#define MPU6050_GYRO_FS_2000 0x03
+
+#define MPU6050_ACONFIG_XA_ST_BIT 7
+#define MPU6050_ACONFIG_YA_ST_BIT 6
+#define MPU6050_ACONFIG_ZA_ST_BIT 5
+#define MPU6050_ACONFIG_AFS_SEL_BIT 4
+#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2
+#define MPU6050_ACONFIG_ACCEL_HPF_BIT 2
+#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH 3
+
+#define MPU6050_ACCEL_FS_2 0x00
+#define MPU6050_ACCEL_FS_4 0x01
+#define MPU6050_ACCEL_FS_8 0x02
+#define MPU6050_ACCEL_FS_16 0x03
+
+#define MPU6050_DHPF_RESET 0x00
+#define MPU6050_DHPF_5 0x01
+#define MPU6050_DHPF_2P5 0x02
+#define MPU6050_DHPF_1P25 0x03
+#define MPU6050_DHPF_0P63 0x04
+#define MPU6050_DHPF_HOLD 0x07
+
+#define MPU6050_TEMP_FIFO_EN_BIT 7
+#define MPU6050_XG_FIFO_EN_BIT 6
+#define MPU6050_YG_FIFO_EN_BIT 5
+#define MPU6050_ZG_FIFO_EN_BIT 4
+#define MPU6050_ACCEL_FIFO_EN_BIT 3
+#define MPU6050_SLV2_FIFO_EN_BIT 2
+#define MPU6050_SLV1_FIFO_EN_BIT 1
+#define MPU6050_SLV0_FIFO_EN_BIT 0
+
+#define MPU6050_MULT_MST_EN_BIT 7
+#define MPU6050_WAIT_FOR_ES_BIT 6
+#define MPU6050_SLV_3_FIFO_EN_BIT 5
+#define MPU6050_I2C_MST_P_NSR_BIT 4
+#define MPU6050_I2C_MST_CLK_BIT 3
+#define MPU6050_I2C_MST_CLK_LENGTH 4
+
+#define MPU6050_CLOCK_DIV_348 0x0
+#define MPU6050_CLOCK_DIV_333 0x1
+#define MPU6050_CLOCK_DIV_320 0x2
+#define MPU6050_CLOCK_DIV_308 0x3
+#define MPU6050_CLOCK_DIV_296 0x4
+#define MPU6050_CLOCK_DIV_286 0x5
+#define MPU6050_CLOCK_DIV_276 0x6
+#define MPU6050_CLOCK_DIV_267 0x7
+#define MPU6050_CLOCK_DIV_258 0x8
+#define MPU6050_CLOCK_DIV_500 0x9
+#define MPU6050_CLOCK_DIV_471 0xA
+#define MPU6050_CLOCK_DIV_444 0xB
+#define MPU6050_CLOCK_DIV_421 0xC
+#define MPU6050_CLOCK_DIV_400 0xD
+#define MPU6050_CLOCK_DIV_381 0xE
+#define MPU6050_CLOCK_DIV_364 0xF
+
+#define MPU6050_I2C_SLV_RW_BIT 7
+#define MPU6050_I2C_SLV_ADDR_BIT 6
+#define MPU6050_I2C_SLV_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV_EN_BIT 7
+#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
+#define MPU6050_I2C_SLV_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV_GRP_BIT 4
+#define MPU6050_I2C_SLV_LEN_BIT 3
+#define MPU6050_I2C_SLV_LEN_LENGTH 4
+
+#define MPU6050_I2C_SLV4_RW_BIT 7
+#define MPU6050_I2C_SLV4_ADDR_BIT 6
+#define MPU6050_I2C_SLV4_ADDR_LENGTH 7
+#define MPU6050_I2C_SLV4_EN_BIT 7
+#define MPU6050_I2C_SLV4_INT_EN_BIT 6
+#define MPU6050_I2C_SLV4_REG_DIS_BIT 5
+#define MPU6050_I2C_SLV4_MST_DLY_BIT 4
+#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU6050_MST_PASS_THROUGH_BIT 7
+#define MPU6050_MST_I2C_SLV4_DONE_BIT 6
+#define MPU6050_MST_I2C_LOST_ARB_BIT 5
+#define MPU6050_MST_I2C_SLV4_NACK_BIT 4
+#define MPU6050_MST_I2C_SLV3_NACK_BIT 3
+#define MPU6050_MST_I2C_SLV2_NACK_BIT 2
+#define MPU6050_MST_I2C_SLV1_NACK_BIT 1
+#define MPU6050_MST_I2C_SLV0_NACK_BIT 0
+
+#define MPU6050_INTCFG_INT_LEVEL_BIT 7
+#define MPU6050_INTCFG_INT_OPEN_BIT 6
+#define MPU6050_INTCFG_LATCH_INT_EN_BIT 5
+#define MPU6050_INTCFG_INT_RD_CLEAR_BIT 4
+#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT 3
+#define MPU6050_INTCFG_FSYNC_INT_EN_BIT 2
+#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT 1
+#define MPU6050_INTCFG_CLKOUT_EN_BIT 0
+
+#define MPU6050_INTMODE_ACTIVEHIGH 0x00
+#define MPU6050_INTMODE_ACTIVELOW 0x01
+
+#define MPU6050_INTDRV_PUSHPULL 0x00
+#define MPU6050_INTDRV_OPENDRAIN 0x01
+
+#define MPU6050_INTLATCH_50USPULSE 0x00
+#define MPU6050_INTLATCH_WAITCLEAR 0x01
+
+#define MPU6050_INTCLEAR_STATUSREAD 0x00
+#define MPU6050_INTCLEAR_ANYREAD 0x01
+
+#define MPU6050_INTERRUPT_FF_BIT 7
+#define MPU6050_INTERRUPT_MOT_BIT 6
+#define MPU6050_INTERRUPT_ZMOT_BIT 5
+#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT 4
+#define MPU6050_INTERRUPT_I2C_MST_INT_BIT 3
+#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT 2
+#define MPU6050_INTERRUPT_DMP_INT_BIT 1
+#define MPU6050_INTERRUPT_DATA_RDY_BIT 0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU6050_DMPINT_5_BIT 5
+#define MPU6050_DMPINT_4_BIT 4
+#define MPU6050_DMPINT_3_BIT 3
+#define MPU6050_DMPINT_2_BIT 2
+#define MPU6050_DMPINT_1_BIT 1
+#define MPU6050_DMPINT_0_BIT 0
+
+#define MPU6050_MOTION_MOT_XNEG_BIT 7
+#define MPU6050_MOTION_MOT_XPOS_BIT 6
+#define MPU6050_MOTION_MOT_YNEG_BIT 5
+#define MPU6050_MOTION_MOT_YPOS_BIT 4
+#define MPU6050_MOTION_MOT_ZNEG_BIT 3
+#define MPU6050_MOTION_MOT_ZPOS_BIT 2
+#define MPU6050_MOTION_MOT_ZRMOT_BIT 0
+
+#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT 7
+#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4
+#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3
+#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2
+#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1
+#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0
+
+#define MPU6050_PATHRESET_GYRO_RESET_BIT 2
+#define MPU6050_PATHRESET_ACCEL_RESET_BIT 1
+#define MPU6050_PATHRESET_TEMP_RESET_BIT 0
+
+#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT 5
+#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH 2
+#define MPU6050_DETECT_FF_COUNT_BIT 3
+#define MPU6050_DETECT_FF_COUNT_LENGTH 2
+#define MPU6050_DETECT_MOT_COUNT_BIT 1
+#define MPU6050_DETECT_MOT_COUNT_LENGTH 2
+
+#define MPU6050_DETECT_DECREMENT_RESET 0x0
+#define MPU6050_DETECT_DECREMENT_1 0x1
+#define MPU6050_DETECT_DECREMENT_2 0x2
+#define MPU6050_DETECT_DECREMENT_4 0x3
+
+#define MPU6050_USERCTRL_DMP_EN_BIT 7
+#define MPU6050_USERCTRL_FIFO_EN_BIT 6
+#define MPU6050_USERCTRL_I2C_MST_EN_BIT 5
+#define MPU6050_USERCTRL_I2C_IF_DIS_BIT 4
+#define MPU6050_USERCTRL_DMP_RESET_BIT 3
+#define MPU6050_USERCTRL_FIFO_RESET_BIT 2
+#define MPU6050_USERCTRL_I2C_MST_RESET_BIT 1
+#define MPU6050_USERCTRL_SIG_COND_RESET_BIT 0
+
+#define MPU6050_PWR1_DEVICE_RESET_BIT 7
+#define MPU6050_PWR1_SLEEP_BIT 6
+#define MPU6050_PWR1_CYCLE_BIT 5
+#define MPU6050_PWR1_TEMP_DIS_BIT 3
+#define MPU6050_PWR1_CLKSEL_BIT 2
+#define MPU6050_PWR1_CLKSEL_LENGTH 3
+
+#define MPU6050_CLOCK_INTERNAL 0x00
+#define MPU6050_CLOCK_PLL_XGYRO 0x01
+#define MPU6050_CLOCK_PLL_YGYRO 0x02
+#define MPU6050_CLOCK_PLL_ZGYRO 0x03
+#define MPU6050_CLOCK_PLL_EXT32K 0x04
+#define MPU6050_CLOCK_PLL_EXT19M 0x05
+#define MPU6050_CLOCK_KEEP_RESET 0x07
+
+#define MPU6050_PWR2_LP_WAKE_CTRL_BIT 7
+#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH 2
+#define MPU6050_PWR2_STBY_XA_BIT 5
+#define MPU6050_PWR2_STBY_YA_BIT 4
+#define MPU6050_PWR2_STBY_ZA_BIT 3
+#define MPU6050_PWR2_STBY_XG_BIT 2
+#define MPU6050_PWR2_STBY_YG_BIT 1
+#define MPU6050_PWR2_STBY_ZG_BIT 0
+
+#define MPU6050_WAKE_FREQ_1P25 0x0
+#define MPU6050_WAKE_FREQ_2P5 0x1
+#define MPU6050_WAKE_FREQ_5 0x2
+#define MPU6050_WAKE_FREQ_10 0x3
+
+#define MPU6050_BANKSEL_PRFTCH_EN_BIT 6
+#define MPU6050_BANKSEL_CFG_USER_BANK_BIT 5
+#define MPU6050_BANKSEL_MEM_SEL_BIT 4
+#define MPU6050_BANKSEL_MEM_SEL_LENGTH 5
+
+#define MPU6050_WHO_AM_I_BIT 6
+#define MPU6050_WHO_AM_I_LENGTH 6
+
+#define MPU6050_DMP_MEMORY_BANKS 8
+#define MPU6050_DMP_MEMORY_BANK_SIZE 256
+#define MPU6050_DMP_MEMORY_CHUNK_SIZE 16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU6050 {
+ private:
+ I2Cdev i2Cdev;
+ Serial debugSerial;
+ public:
+ MPU6050();
+ MPU6050(uint8_t address);
+
+ void initialize();
+ bool testConnection();
+
+ // AUX_VDDIO register
+ uint8_t getAuxVDDIOLevel();
+ void setAuxVDDIOLevel(uint8_t level);
+
+ // SMPLRT_DIV register
+ uint8_t getRate();
+ void setRate(uint8_t rate);
+
+ // CONFIG register
+ uint8_t getExternalFrameSync();
+ void setExternalFrameSync(uint8_t sync);
+ uint8_t getDLPFMode();
+ void setDLPFMode(uint8_t bandwidth);
+
+ // GYRO_CONFIG register
+ uint8_t getFullScaleGyroRange();
+ void setFullScaleGyroRange(uint8_t range);
+
+ // ACCEL_CONFIG register
+ bool getAccelXSelfTest();
+ void setAccelXSelfTest(bool enabled);
+ bool getAccelYSelfTest();
+ void setAccelYSelfTest(bool enabled);
+ bool getAccelZSelfTest();
+ void setAccelZSelfTest(bool enabled);
+ uint8_t getFullScaleAccelRange();
+ void setFullScaleAccelRange(uint8_t range);
+ uint8_t getDHPFMode();
+ void setDHPFMode(uint8_t mode);
+
+ // FF_THR register
+ uint8_t getFreefallDetectionThreshold();
+ void setFreefallDetectionThreshold(uint8_t threshold);
+
+ // FF_DUR register
+ uint8_t getFreefallDetectionDuration();
+ void setFreefallDetectionDuration(uint8_t duration);
+
+ // MOT_THR register
+ uint8_t getMotionDetectionThreshold();
+ void setMotionDetectionThreshold(uint8_t threshold);
+
+ // MOT_DUR register
+ uint8_t getMotionDetectionDuration();
+ void setMotionDetectionDuration(uint8_t duration);
+
+ // ZRMOT_THR register
+ uint8_t getZeroMotionDetectionThreshold();
+ void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+ // ZRMOT_DUR register
+ uint8_t getZeroMotionDetectionDuration();
+ void setZeroMotionDetectionDuration(uint8_t duration);
+
+ // FIFO_EN register
+ bool getTempFIFOEnabled();
+ void setTempFIFOEnabled(bool enabled);
+ bool getXGyroFIFOEnabled();
+ void setXGyroFIFOEnabled(bool enabled);
+ bool getYGyroFIFOEnabled();
+ void setYGyroFIFOEnabled(bool enabled);
+ bool getZGyroFIFOEnabled();
+ void setZGyroFIFOEnabled(bool enabled);
+ bool getAccelFIFOEnabled();
+ void setAccelFIFOEnabled(bool enabled);
+ bool getSlave2FIFOEnabled();
+ void setSlave2FIFOEnabled(bool enabled);
+ bool getSlave1FIFOEnabled();
+ void setSlave1FIFOEnabled(bool enabled);
+ bool getSlave0FIFOEnabled();
+ void setSlave0FIFOEnabled(bool enabled);
+
+ // I2C_MST_CTRL register
+ bool getMultiMasterEnabled();
+ void setMultiMasterEnabled(bool enabled);
+ bool getWaitForExternalSensorEnabled();
+ void setWaitForExternalSensorEnabled(bool enabled);
+ bool getSlave3FIFOEnabled();
+ void setSlave3FIFOEnabled(bool enabled);
+ bool getSlaveReadWriteTransitionEnabled();
+ void setSlaveReadWriteTransitionEnabled(bool enabled);
+ uint8_t getMasterClockSpeed();
+ void setMasterClockSpeed(uint8_t speed);
+
+ // I2C_SLV* registers (Slave 0-3)
+ uint8_t getSlaveAddress(uint8_t num);
+ void setSlaveAddress(uint8_t num, uint8_t address);
+ uint8_t getSlaveRegister(uint8_t num);
+ void setSlaveRegister(uint8_t num, uint8_t reg);
+ bool getSlaveEnabled(uint8_t num);
+ void setSlaveEnabled(uint8_t num, bool enabled);
+ bool getSlaveWordByteSwap(uint8_t num);
+ void setSlaveWordByteSwap(uint8_t num, bool enabled);
+ bool getSlaveWriteMode(uint8_t num);
+ void setSlaveWriteMode(uint8_t num, bool mode);
+ bool getSlaveWordGroupOffset(uint8_t num);
+ void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+ uint8_t getSlaveDataLength(uint8_t num);
+ void setSlaveDataLength(uint8_t num, uint8_t length);
+
+ // I2C_SLV* registers (Slave 4)
+ uint8_t getSlave4Address();
+ void setSlave4Address(uint8_t address);
+ uint8_t getSlave4Register();
+ void setSlave4Register(uint8_t reg);
+ void setSlave4OutputByte(uint8_t data);
+ bool getSlave4Enabled();
+ void setSlave4Enabled(bool enabled);
+ bool getSlave4InterruptEnabled();
+ void setSlave4InterruptEnabled(bool enabled);
+ bool getSlave4WriteMode();
+ void setSlave4WriteMode(bool mode);
+ uint8_t getSlave4MasterDelay();
+ void setSlave4MasterDelay(uint8_t delay);
+ uint8_t getSlate4InputByte();
+
+ // I2C_MST_STATUS register
+ bool getPassthroughStatus();
+ bool getSlave4IsDone();
+ bool getLostArbitration();
+ bool getSlave4Nack();
+ bool getSlave3Nack();
+ bool getSlave2Nack();
+ bool getSlave1Nack();
+ bool getSlave0Nack();
+
+ // INT_PIN_CFG register
+ bool getInterruptMode();
+ void setInterruptMode(bool mode);
+ bool getInterruptDrive();
+ void setInterruptDrive(bool drive);
+ bool getInterruptLatch();
+ void setInterruptLatch(bool latch);
+ bool getInterruptLatchClear();
+ void setInterruptLatchClear(bool clear);
+ bool getFSyncInterruptLevel();
+ void setFSyncInterruptLevel(bool level);
+ bool getFSyncInterruptEnabled();
+ void setFSyncInterruptEnabled(bool enabled);
+ bool getI2CBypassEnabled();
+ void setI2CBypassEnabled(bool enabled);
+ bool getClockOutputEnabled();
+ void setClockOutputEnabled(bool enabled);
+
+ // INT_ENABLE register
+ uint8_t getIntEnabled();
+ void setIntEnabled(uint8_t enabled);
+ bool getIntFreefallEnabled();
+ void setIntFreefallEnabled(bool enabled);
+ bool getIntMotionEnabled();
+ void setIntMotionEnabled(bool enabled);
+ bool getIntZeroMotionEnabled();
+ void setIntZeroMotionEnabled(bool enabled);
+ bool getIntFIFOBufferOverflowEnabled();
+ void setIntFIFOBufferOverflowEnabled(bool enabled);
+ bool getIntI2CMasterEnabled();
+ void setIntI2CMasterEnabled(bool enabled);
+ bool getIntDataReadyEnabled();
+ void setIntDataReadyEnabled(bool enabled);
+
+ // INT_STATUS register
+ uint8_t getIntStatus();
+ bool getIntFreefallStatus();
+ bool getIntMotionStatus();
+ bool getIntZeroMotionStatus();
+ bool getIntFIFOBufferOverflowStatus();
+ bool getIntI2CMasterStatus();
+ bool getIntDataReadyStatus();
+
+ // ACCEL_*OUT_* registers
+ void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+ void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+ void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+ int16_t getAccelerationX();
+ int16_t getAccelerationY();
+ int16_t getAccelerationZ();
+
+ // TEMP_OUT_* registers
+ int16_t getTemperature();
+
+ // GYRO_*OUT_* registers
+ void getRotation(int16_t* x, int16_t* y, int16_t* z);
+ int16_t getRotationX();
+ int16_t getRotationY();
+ int16_t getRotationZ();
+
+ // EXT_SENS_DATA_* registers
+ uint8_t getExternalSensorByte(int position);
+ uint16_t getExternalSensorWord(int position);
+ uint32_t getExternalSensorDWord(int position);
+
+ // MOT_DETECT_STATUS register
+ bool getXNegMotionDetected();
+ bool getXPosMotionDetected();
+ bool getYNegMotionDetected();
+ bool getYPosMotionDetected();
+ bool getZNegMotionDetected();
+ bool getZPosMotionDetected();
+ bool getZeroMotionDetected();
+
+ // I2C_SLV*_DO register
+ void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+ // I2C_MST_DELAY_CTRL register
+ bool getExternalShadowDelayEnabled();
+ void setExternalShadowDelayEnabled(bool enabled);
+ bool getSlaveDelayEnabled(uint8_t num);
+ void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+ // SIGNAL_PATH_RESET register
+ void resetGyroscopePath();
+ void resetAccelerometerPath();
+ void resetTemperaturePath();
+
+ // MOT_DETECT_CTRL register
+ uint8_t getAccelerometerPowerOnDelay();
+ void setAccelerometerPowerOnDelay(uint8_t delay);
+ uint8_t getFreefallDetectionCounterDecrement();
+ void setFreefallDetectionCounterDecrement(uint8_t decrement);
+ uint8_t getMotionDetectionCounterDecrement();
+ void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+ // USER_CTRL register
+ bool getFIFOEnabled();
+ void setFIFOEnabled(bool enabled);
+ bool getI2CMasterModeEnabled();
+ void setI2CMasterModeEnabled(bool enabled);
+ void switchSPIEnabled(bool enabled);
+ void resetFIFO();
+ void resetI2CMaster();
+ void resetSensors();
+
+ // PWR_MGMT_1 register
+ void reset();
+ bool getSleepEnabled();
+ void setSleepEnabled(bool enabled);
+ bool getWakeCycleEnabled();
+ void setWakeCycleEnabled(bool enabled);
+ bool getTempSensorEnabled();
+ void setTempSensorEnabled(bool enabled);
+ uint8_t getClockSource();
+ void setClockSource(uint8_t source);
+
+ // PWR_MGMT_2 register
+ uint8_t getWakeFrequency();
+ void setWakeFrequency(uint8_t frequency);
+ bool getStandbyXAccelEnabled();
+ void setStandbyXAccelEnabled(bool enabled);
+ bool getStandbyYAccelEnabled();
+ void setStandbyYAccelEnabled(bool enabled);
+ bool getStandbyZAccelEnabled();
+ void setStandbyZAccelEnabled(bool enabled);
+ bool getStandbyXGyroEnabled();
+ void setStandbyXGyroEnabled(bool enabled);
+ bool getStandbyYGyroEnabled();
+ void setStandbyYGyroEnabled(bool enabled);
+ bool getStandbyZGyroEnabled();
+ void setStandbyZGyroEnabled(bool enabled);
+
+ // FIFO_COUNT_* registers
+ uint16_t getFIFOCount();
+
+ // FIFO_R_W register
+ uint8_t getFIFOByte();
+ void setFIFOByte(uint8_t data);
+ void getFIFOBytes(uint8_t *data, uint8_t length);
+
+ // WHO_AM_I register
+ uint8_t getDeviceID();
+ void setDeviceID(uint8_t id);
+
+ // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+ // XG_OFFS_TC register
+ uint8_t getOTPBankValid();
+ void setOTPBankValid(bool enabled);
+ int8_t getXGyroOffset();
+ void setXGyroOffset(int8_t offset);
+
+ // YG_OFFS_TC register
+ int8_t getYGyroOffset();
+ void setYGyroOffset(int8_t offset);
+
+ // ZG_OFFS_TC register
+ int8_t getZGyroOffset();
+ void setZGyroOffset(int8_t offset);
+
+ // X_FINE_GAIN register
+ int8_t getXFineGain();
+ void setXFineGain(int8_t gain);
+
+ // Y_FINE_GAIN register
+ int8_t getYFineGain();
+ void setYFineGain(int8_t gain);
+
+ // Z_FINE_GAIN register
+ int8_t getZFineGain();
+ void setZFineGain(int8_t gain);
+
+ // XA_OFFS_* registers
+ int16_t getXAccelOffset();
+ void setXAccelOffset(int16_t offset);
+
+ // YA_OFFS_* register
+ int16_t getYAccelOffset();
+ void setYAccelOffset(int16_t offset);
+
+ // ZA_OFFS_* register
+ int16_t getZAccelOffset();
+ void setZAccelOffset(int16_t offset);
+
+ // XG_OFFS_USR* registers
+ int16_t getXGyroOffsetUser();
+ void setXGyroOffsetUser(int16_t offset);
+
+ // YG_OFFS_USR* register
+ int16_t getYGyroOffsetUser();
+ void setYGyroOffsetUser(int16_t offset);
+
+ // ZG_OFFS_USR* register
+ int16_t getZGyroOffsetUser();
+ void setZGyroOffsetUser(int16_t offset);
+
+ // INT_ENABLE register (DMP functions)
+ bool getIntPLLReadyEnabled();
+ void setIntPLLReadyEnabled(bool enabled);
+ bool getIntDMPEnabled();
+ void setIntDMPEnabled(bool enabled);
+
+ // DMP_INT_STATUS
+ bool getDMPInt5Status();
+ bool getDMPInt4Status();
+ bool getDMPInt3Status();
+ bool getDMPInt2Status();
+ bool getDMPInt1Status();
+ bool getDMPInt0Status();
+
+ // INT_STATUS register (DMP functions)
+ bool getIntPLLReadyStatus();
+ bool getIntDMPStatus();
+
+ // USER_CTRL register (DMP functions)
+ bool getDMPEnabled();
+ void setDMPEnabled(bool enabled);
+ void resetDMP();
+
+ // BANK_SEL register
+ void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+
+ // MEM_START_ADDR register
+ void setMemoryStartAddress(uint8_t address);
+
+ // MEM_R_W register
+ uint8_t readMemoryByte();
+ void writeMemoryByte(uint8_t data);
+ void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+ bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+ bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+ bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+ bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+ // DMP_CFG_1 register
+ uint8_t getDMPConfig1();
+ void setDMPConfig1(uint8_t config);
+
+ // DMP_CFG_2 register
+ uint8_t getDMPConfig2();
+ void setDMPConfig2(uint8_t config);
+
+ // special methods for MotionApps 2.0 implementation
+ #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20
+ uint8_t *dmpPacketBuffer;
+ uint16_t dmpPacketSize;
+
+ uint8_t dmpInitialize();
+ bool dmpPacketAvailable();
+
+ uint8_t dmpSetFIFORate(uint8_t fifoRate);
+ uint8_t dmpGetFIFORate();
+ uint8_t dmpGetSampleStepSizeMS();
+ uint8_t dmpGetSampleFrequency();
+ int32_t dmpDecodeTemperature(int8_t tempReg);
+
+ // Register callbacks after a packet of FIFO data is processed
+ //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+ //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+ uint8_t dmpRunFIFORateProcesses();
+
+ // Setup FIFO for various output
+ uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+ uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+ uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+ // Get Fixed Point data from FIFO
+ uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+ uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+ uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+ uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+ uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+ uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+
+ uint8_t dmpGetEuler(float *data, Quaternion *q);
+ uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+ // Get Floating Point data from FIFO
+ uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+ uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+ uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+ uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+ uint8_t dmpInitFIFOParam();
+ uint8_t dmpCloseFIFO();
+ uint8_t dmpSetGyroDataSource(uint8_t source);
+ uint8_t dmpDecodeQuantizedAccel();
+ uint32_t dmpGetGyroSumOfSquare();
+ uint32_t dmpGetAccelSumOfSquare();
+ void dmpOverrideQuaternion(long *q);
+ uint16_t dmpGetFIFOPacketSize();
+ #endif
+
+ // special methods for MotionApps 4.1 implementation
+ #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS41
+ uint8_t *dmpPacketBuffer;
+ uint16_t dmpPacketSize;
+
+ uint8_t dmpInitialize();
+ bool dmpPacketAvailable();
+
+ uint8_t dmpSetFIFORate(uint8_t fifoRate);
+ uint8_t dmpGetFIFORate();
+ uint8_t dmpGetSampleStepSizeMS();
+ uint8_t dmpGetSampleFrequency();
+ int32_t dmpDecodeTemperature(int8_t tempReg);
+
+ // Register callbacks after a packet of FIFO data is processed
+ //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+ //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+ uint8_t dmpRunFIFORateProcesses();
+
+ // Setup FIFO for various output
+ uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+ uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+ uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+ uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+ // Get Fixed Point data from FIFO
+ uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+ uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+ uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+ uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+ uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+ uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+ uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+
+ uint8_t dmpGetEuler(float *data, Quaternion *q);
+ uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+ // Get Floating Point data from FIFO
+ uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+ uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+ uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+ uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+ uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+ uint8_t dmpInitFIFOParam();
+ uint8_t dmpCloseFIFO();
+ uint8_t dmpSetGyroDataSource(uint8_t source);
+ uint8_t dmpDecodeQuantizedAccel();
+ uint32_t dmpGetGyroSumOfSquare();
+ uint32_t dmpGetAccelSumOfSquare();
+ void dmpOverrideQuaternion(long *q);
+ uint16_t dmpGetFIFOPacketSize();
+ #endif
+
+ private:
+ uint8_t devAddr;
+ uint8_t buffer[14];
+};
+
+#endif /* _MPU6050_H_ */
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e MPU6050_6Axis_MotionApps20.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU6050_6Axis_MotionApps20.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,751 @@
+// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 5/20/2013 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// ... - ongoing debug release
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+#ifndef _MPU6050_6AXIS_MOTIONAPPS20_H_
+#define _MPU6050_6AXIS_MOTIONAPPS20_H_
+
+#include <iostream>
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS20
+
+#include "MPU6050.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifndef __arm__
+ #include <avr/pgmspace.h>
+#else
+ // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+ #ifndef __PGMSPACE_H_
+ #define __PGMSPACE_H_ 1
+ #include <inttypes.h>
+
+ #define PROGMEM
+ #define PGM_P const char *
+ #define PSTR(str) (str)
+ #define F(x) x
+
+ typedef void prog_void;
+ typedef char prog_char;
+ typedef unsigned char prog_uchar;
+ typedef int8_t prog_int8_t;
+ typedef uint8_t prog_uint8_t;
+ typedef int16_t prog_int16_t;
+ typedef uint16_t prog_uint16_t;
+ typedef int32_t prog_int32_t;
+ typedef uint32_t prog_uint32_t;
+
+ #define strcpy_P(dest, src) strcpy((dest), (src))
+ #define strcat_P(dest, src) strcat((dest), (src))
+ #define strcmp_P(a, b) strcmp((a), (b))
+
+ #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+ #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+ #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+ #define pgm_read_float(addr) (*(const float *)(addr))
+
+ #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+ #define pgm_read_word_near(addr) pgm_read_word(addr)
+ #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+ #define pgm_read_float_near(addr) pgm_read_float(addr)
+ #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+ #define pgm_read_word_far(addr) pgm_read_word(addr)
+ #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+ #define pgm_read_float_far(addr) pgm_read_float(addr)
+ #endif
+#endif
+
+/* Source is from the InvenSense MotionApps v2 demo code. Original source is
+ * unavailable, unless you happen to be amazing as decompiling binary by
+ * hand (in which case, please contact me, and I'm totally serious).
+ *
+ * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the
+ * DMP reverse-engineering he did to help make this bit of wizardry
+ * possible.
+ */
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+#ifdef DEBUG
+ #define DEBUG_PRINT(x) pc.printf(x) //Serial.print(x)
+ #define DEBUG_PRINTF(x, y) pc.printf(x,y) //Serial.print(x, y)
+
+ #define F(x) x
+#else
+ #define DEBUG_PRINT(x)
+ #define DEBUG_PRINTF(x, y)
+
+#endif
+
+#define MPU6050_DMP_CODE_SIZE 1929 // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE 192 // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE 47 // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v2.0 42-byte FIFO packet structure: |
+ | |
+ | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] |
+ | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 |
+ | |
+ | [GYRO Z][ ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] |
+ | 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+ // bank 0, 256 bytes
+ 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+ 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+ 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+ 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+ 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+ 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+ 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+ 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+ // bank 1, 256 bytes
+ 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+ 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+ 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+ 0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+ // bank 2, 256 bytes
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+ // bank 3, 256 bytes
+ 0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
+ 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
+ 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
+ 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
+ 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
+ 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
+ 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
+ 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
+ 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
+ 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
+ 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
+ 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
+ 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
+ 0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
+ 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+ 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+
+ // bank 4, 256 bytes
+ 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+ 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+ 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+ 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+ 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+ 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+ 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+ 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+ 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+ 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+ 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+ 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+
+ // bank 5, 256 bytes
+ 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+ 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+ 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+ 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+ 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+ 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+ 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+ 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+ 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
+ 0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
+ 0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
+ 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
+ 0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
+ 0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
+ 0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
+ 0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
+
+ // bank 6, 256 bytes
+ 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
+ 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
+ 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
+ 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
+ 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
+ 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
+ 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
+ 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
+ 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
+ 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
+ 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
+ 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
+ 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
+ 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
+ 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
+ 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
+
+ // bank 7, 138 bytes (remainder)
+ 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
+ 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
+ 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
+ 0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
+ 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
+ 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
+ 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+// thanks to Noah Zerkin for piecing this stuff together!
+const unsigned char dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+// BANK OFFSET LENGTH [DATA]
+ 0x03, 0x7B, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration
+ 0x03, 0xAB, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration
+ 0x00, 0x68, 0x04, 0x02, 0xCB, 0x47, 0xA2, // D_0_104 inv_set_gyro_calibration
+ 0x02, 0x18, 0x04, 0x00, 0x05, 0x8B, 0xC1, // D_0_24 inv_set_gyro_calibration
+ 0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration
+ 0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
+ 0x03, 0x89, 0x03, 0x26, 0x46, 0x66, // FCFG_7 inv_set_accel_calibration
+ 0x00, 0x6C, 0x02, 0x20, 0x00, // D_0_108 inv_set_accel_calibration
+ 0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration
+ 0x02, 0x44, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_01
+ 0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02
+ 0x02, 0x4C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_10
+ 0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11
+ 0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12
+ 0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20
+ 0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21
+ 0x02, 0xBC, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_22
+ 0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel
+ 0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+ 0x04, 0x02, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+ 0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update
+ 0x00, 0xA3, 0x01, 0x00, // D_0_163 inv_set_dead_zone
+ // SPECIAL 0x01 = enable interrupts
+ 0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
+ 0x07, 0x86, 0x01, 0xFE, // CFG_6 inv_set_fifo_interupt
+ 0x07, 0x41, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+ 0x07, 0x7E, 0x01, 0x30, // CFG_16 inv_set_footer
+ 0x07, 0x46, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro
+ 0x07, 0x47, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo
+ 0x07, 0x6C, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo
+ 0x02, 0x16, 0x02, 0x00, 0x01 // D_0_22 inv_set_fifo_rate
+
+ // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+ // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+ // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+ // It is important to make sure the host processor can keep up with reading and processing
+ // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const unsigned char dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
+ 0x01, 0xB2, 0x02, 0xFF, 0xFF,
+ 0x01, 0x90, 0x04, 0x09, 0x23, 0xA1, 0x35,
+ 0x01, 0x6A, 0x02, 0x06, 0x00,
+ 0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
+ 0x01, 0x62, 0x02, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00
+};
+
+uint8_t MPU6050::dmpInitialize() {
+ // reset device
+ Serial pc(USBTX, USBRX); // tx, rx
+ pc.baud(115200);
+ wait_ms(50);
+
+ pc.printf("\n\nSet USB Baudrate to 115200...\n");
+
+ pc.printf("\n\nResetting MPU6050...\n");
+ reset();
+
+ wait_ms(30);
+
+ // enable sleep mode and wake cycle
+ /*Serial.println(F("Enabling sleep mode..."));
+ setSleepEnabled(true);
+ Serial.println(F("Enabling wake cycle..."));
+ setWakeCycleEnabled(true);*/
+
+ // disable sleep mode
+ DEBUG_PRINT("Disabling sleep mode...\n");
+ setSleepEnabled(false);
+
+ // get MPU hardware revision
+ DEBUG_PRINT("Selecting user bank 16...\n");
+ setMemoryBank(0x10, true, true);
+ DEBUG_PRINT("Selecting memory byte 6...\n");
+ setMemoryStartAddress(0x06);
+ DEBUG_PRINT("Checking hardware revision...\n");
+ uint8_t hwRevision = readMemoryByte();
+ DEBUG_PRINT("Revision @ user[16][6] = ");
+ DEBUG_PRINTF("%x\n",hwRevision);
+ DEBUG_PRINT("Resetting memory bank selection to 0...\n");
+ setMemoryBank(0, false, false);
+
+ // check OTP bank valid
+ DEBUG_PRINT("Reading OTP bank valid flag...\n");
+ uint8_t otpValid = getOTPBankValid();
+
+ DEBUG_PRINT("OTP bank is ");
+ if(otpValid) DEBUG_PRINT("valid!\n");
+ else DEBUG_PRINT("invalid!\n");
+
+ // get X/Y/Z gyro offsets
+ /*
+ DEBUG_PRINT("\nReading gyro offset TC values...\n");
+ int8_t xgOffsetTC = mpu.getXGyroOffsetTC();
+ int8_t ygOffsetTC = getYGyroOffsetTC();
+ int8_t zgOffsetTC = getZGyroOffsetTC();
+ DEBUG_PRINTF("X gyro offset = %u\n",xgOffset);
+ DEBUG_PRINTF("Y gyro offset = %u\n",ygOffset);
+ DEBUG_PRINTF("Z gyro offset = %u\n",zgOffset);
+ */
+ // setup weird slave stuff (?)
+ DEBUG_PRINT("Setting slave 0 address to 0x7F...\n");
+ setSlaveAddress(0, 0x7F);
+
+ DEBUG_PRINT("Disabling I2C Master mode...");
+ setI2CMasterModeEnabled(false);
+ DEBUG_PRINT("Setting slave 0 address to 0x68 (self)...");
+ setSlaveAddress(0, 0x68);
+ DEBUG_PRINT("Resetting I2C Master control...\n");
+ resetI2CMaster();
+
+ wait_ms(20);
+
+ // load DMP code into memory banks
+ DEBUG_PRINT("Writing DMP code to MPU memory banks (");
+ DEBUG_PRINTF("%u",MPU6050_DMP_CODE_SIZE);
+ DEBUG_PRINT(" bytes)\n");
+ if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) {
+ DEBUG_PRINT("Success! DMP code written and verified.\n");
+
+ // write DMP configuration
+ DEBUG_PRINT("Writing DMP configuration to MPU memory banks (");
+ DEBUG_PRINTF("%u",MPU6050_DMP_CONFIG_SIZE);
+ DEBUG_PRINT(" bytes in config def)\n");
+ if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) {
+ DEBUG_PRINT("Success! DMP configuration written and verified.\n");
+
+ DEBUG_PRINT("Setting clock source to Z Gyro...\n");
+ setClockSource(MPU6050_CLOCK_PLL_ZGYRO);
+
+ DEBUG_PRINT("Setting DMP and FIFO_OFLOW interrupts enabled...\n");
+ setIntEnabled(0x12);
+
+ DEBUG_PRINT("Setting sample rate to 200Hz...");
+ setRate(4); // 1khz / (1 + 4) = 200 Hz
+
+ DEBUG_PRINT("Setting external frame sync to TEMP_OUT_L[0]...\n");
+ setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L);
+
+ DEBUG_PRINT("Setting DLPF bandwidth to 42Hz...\n");
+ setDLPFMode(MPU6050_DLPF_BW_42);
+
+ DEBUG_PRINT("Setting gyro sensitivity to +/- 2000 deg/sec...\n");
+ setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+
+ DEBUG_PRINT("Setting DMP configuration bytes (function unknown)...\n");
+ setDMPConfig1(0x03);
+ setDMPConfig2(0x00);
+
+ DEBUG_PRINT("Clearing OTP Bank flag...");
+ setOTPBankValid(false);
+
+ DEBUG_PRINT("Setting X/Y/Z gyro offset TCs to previous values...\n");
+ //setXGyroOffsetTC(xgOffsetTC);
+ //setYGyroOffsetTC(ygOffsetTC);
+ //setZGyroOffsetTC(zgOffsetTC);
+
+ //DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero..."));
+ //setXGyroOffset(0);
+ //setYGyroOffset(0);
+ //setZGyroOffset(0);
+
+ DEBUG_PRINT("Writing final memory update 1/7 (function unknown)...\n");
+ uint8_t dmpUpdate[16], j;
+ uint16_t pos = 0;
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Writing final memory update 2/7 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Resetting FIFO...\n");
+ resetFIFO();
+
+ DEBUG_PRINT("Reading FIFO count...\n");
+ uint16_t fifoCount = getFIFOCount();
+ uint8_t fifoBuffer[128];
+
+ DEBUG_PRINT("Current FIFO count=");
+ DEBUG_PRINTF("%u\n",fifoCount);
+ getFIFOBytes(fifoBuffer, fifoCount);
+
+ DEBUG_PRINT("Setting motion detection threshold to 2...\n");
+ setMotionDetectionThreshold(2);
+
+ DEBUG_PRINT("Setting zero-motion detection threshold to 156...\n");
+ setZeroMotionDetectionThreshold(156);
+
+ DEBUG_PRINT("Setting motion detection duration to 80...");
+ setMotionDetectionDuration(80);
+
+ DEBUG_PRINT("Setting zero-motion detection duration to 0...");
+ setZeroMotionDetectionDuration(0);
+
+ DEBUG_PRINT("Resetting FIFO...\n");
+ resetFIFO();
+
+ DEBUG_PRINT("Enabling FIFO...\n");
+ setFIFOEnabled(true);
+
+ DEBUG_PRINT("Enabling DMP...\n");
+ setDMPEnabled(true);
+
+ DEBUG_PRINT("Resetting DMP...\n");
+ resetDMP();
+
+ DEBUG_PRINT("Writing final memory update 3/7 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Writing final memory update 4/7 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Writing final memory update 5/7 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+ while ((fifoCount = getFIFOCount()) < 3);
+
+ DEBUG_PRINT("Current FIFO count=");
+ DEBUG_PRINTF("%u\n",fifoCount);
+ DEBUG_PRINT("Reading FIFO data...\n");
+ getFIFOBytes(fifoBuffer, fifoCount);
+
+ DEBUG_PRINT("Reading interrupt status...\n");
+ uint8_t mpuIntStatus = getIntStatus();
+
+ DEBUG_PRINT("Current interrupt status=");
+ DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+ DEBUG_PRINT("Reading final memory update 6/7 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Waiting for FIFO count > 2...\n");
+ while ((fifoCount = getFIFOCount()) < 3);
+
+ DEBUG_PRINT("Current FIFO count=");
+ DEBUG_PRINTF("%u\n",fifoCount);
+
+ DEBUG_PRINT("Reading FIFO data...\n");
+ getFIFOBytes(fifoBuffer, fifoCount);
+
+ DEBUG_PRINT("Reading interrupt status...\n");
+ mpuIntStatus = getIntStatus();
+
+ DEBUG_PRINT("Current interrupt status=");
+ DEBUG_PRINTF("%x\n",mpuIntStatus);
+
+ DEBUG_PRINT("Writing final memory update 7/7 (function unknown)...");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("DMP is good to go! Finally.\n");
+
+ DEBUG_PRINT("Disabling DMP (you turn it on later)...\n");
+ setDMPEnabled(false);
+
+ DEBUG_PRINT("Setting up internal 42-byte (default) DMP packet buffer...\n");
+ dmpPacketSize = 42;
+ /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+ return 3; // TODO: proper error code for no memory
+ }*/
+
+ DEBUG_PRINT("Resetting FIFO and clearing INT status one last time...\n");
+ resetFIFO();
+ getIntStatus();
+ } else {
+ DEBUG_PRINT("ERROR! DMP configuration verification failed.\n");
+ return 2; // configuration block loading failed
+ }
+ } else {
+ DEBUG_PRINT("ERROR! DMP code verification failed.");
+ return 1; // main binary block loading failed
+ }
+ return 0; // success
+}
+
+bool MPU6050::dmpPacketAvailable() {
+ return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[28] << 24) + (packet[29] << 16) + (packet[30] << 8) + packet[31]);
+ data[1] = ((packet[32] << 24) + (packet[33] << 16) + (packet[34] << 8) + packet[35]);
+ data[2] = ((packet[36] << 24) + (packet[37] << 16) + (packet[38] << 8) + packet[39]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[28] << 8) + packet[29];
+ data[1] = (packet[32] << 8) + packet[33];
+ data[2] = (packet[36] << 8) + packet[37];
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = (packet[28] << 8) + packet[29];
+ v -> y = (packet[32] << 8) + packet[33];
+ v -> z = (packet[36] << 8) + packet[37];
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 24) + (packet[1] << 16) + (packet[2] << 8) + packet[3]);
+ data[1] = ((packet[4] << 24) + (packet[5] << 16) + (packet[6] << 8) + packet[7]);
+ data[2] = ((packet[8] << 24) + (packet[9] << 16) + (packet[10] << 8) + packet[11]);
+ data[3] = ((packet[12] << 24) + (packet[13] << 16) + (packet[14] << 8) + packet[15]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 8) + packet[1]);
+ data[1] = ((packet[4] << 8) + packet[5]);
+ data[2] = ((packet[8] << 8) + packet[9]);
+ data[3] = ((packet[12] << 8) + packet[13]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ if (status == 0) {
+ q -> w = (float)qI[0] / 16384.0f;
+ q -> x = (float)qI[1] / 16384.0f;
+ q -> y = (float)qI[2] / 16384.0f;
+ q -> z = (float)qI[3] / 16384.0f;
+ return 0;
+ }
+ return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[16] << 24) + (packet[17] << 16) + (packet[18] << 8) + packet[19]);
+ data[1] = ((packet[20] << 24) + (packet[21] << 16) + (packet[22] << 8) + packet[23]);
+ data[2] = ((packet[24] << 24) + (packet[25] << 16) + (packet[26] << 8) + packet[27]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[16] << 8) + packet[17];
+ data[1] = (packet[20] << 8) + packet[21];
+ data[2] = (packet[24] << 8) + packet[25];
+ return 0;
+}
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+ // get rid of the gravity component (+1g = +8192 in standard DMP FIFO packet, sensitivity is 2g)
+ v -> x = vRaw -> x - gravity -> x*8192;
+ v -> y = vRaw -> y - gravity -> y*8192;
+ v -> z = vRaw -> z - gravity -> z*8192;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+ // rotate measured 3D acceleration vector into original state
+ // frame of reference based on orientation quaternion
+ memcpy(v, vReal, sizeof(VectorInt16));
+ v -> rotate(q);
+ return 0;
+}
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+ v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+ v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+ v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q) {
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi
+ data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta
+ data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi
+ return 0;
+}
+
+uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+ return 0;
+}
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+ /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+ if (dmpData[k] < 0x10) Serial.print("0");
+ Serial.print(dmpData[k], HEX);
+ Serial.print(" ");
+ }
+ Serial.print("\n");*/
+ //Serial.println((uint16_t)dmpPacketBuffer);
+ return 0;
+}
+uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+ uint8_t status;
+ uint8_t buf[dmpPacketSize];
+ for (uint8_t i = 0; i < numPackets; i++) {
+ // read packet from FIFO
+ getFIFOBytes(buf, dmpPacketSize);
+
+ // process packet
+ if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+ // increment external process count variable, if supplied
+ if (processed != 0) *processed++;
+ }
+ return 0;
+}
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050::dmpGetFIFOPacketSize() {
+ return dmpPacketSize;
+}
+
+#endif /* _MPU6050_6AXIS_MOTIONAPPS20_H_ */
diff -r 000000000000 -r e63996fd7d3e MPU6050_9Axis_MotionApps41.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MPU6050_9Axis_MotionApps41.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,865 @@
+// I2Cdev library collection - MPU6050 I2C device class, 9-axis MotionApps 4.1 implementation
+// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 6/18/2012 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// ... - ongoing debug release
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU6050_9AXIS_MOTIONAPPS41_H_
+#define _MPU6050_9AXIS_MOTIONAPPS41_H_
+
+#include <iostream>
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+// MotionApps 4.1 DMP implementation, built using the MPU-9150 "MotionFit" board
+#define MPU6050_INCLUDE_DMP_MOTIONAPPS41
+
+#include "MPU6050.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifndef __arm__
+#include <avr/pgmspace.h>
+#else
+ // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+#ifndef __PGMSPACE_H_
+#define __PGMSPACE_H_ 1
+#include <inttypes.h>
+
+#define PROGMEM
+#define PGM_P const char *
+#define PSTR(str) (str)
+#define F(x) x
+
+ typedef void prog_void;
+ typedef char prog_char;
+ typedef unsigned char prog_uchar;
+ typedef int8_t prog_int8_t;
+ typedef uint8_t prog_uint8_t;
+ typedef int16_t prog_int16_t;
+ typedef uint16_t prog_uint16_t;
+ typedef int32_t prog_int32_t;
+ typedef uint32_t prog_uint32_t;
+#define strcpy_P(dest, src) strcpy((dest), (src))
+#define strcat_P(dest, src) strcat((dest), (src))
+#define strcmp_P(a, b) strcmp((a), (b))
+#define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+#define pgm_read_word(addr) (*(const unsigned short *)(addr))
+#define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+#define pgm_read_float(addr) (*(const float *)(addr))
+#define pgm_read_byte_near(addr) pgm_read_byte(addr)
+#define pgm_read_word_near(addr) pgm_read_word(addr)
+#define pgm_read_dword_near(addr) pgm_read_dword(addr)
+#define pgm_read_float_near(addr) pgm_read_float(addr)
+#define pgm_read_byte_far(addr) pgm_read_byte(addr)
+#define pgm_read_word_far(addr) pgm_read_word(addr)
+#define pgm_read_dword_far(addr) pgm_read_dword(addr)
+#define pgm_read_float_far(addr) pgm_read_float(addr)
+#endif
+#endif
+
+#define min(a,b) (((a)<(b))?(a):(b))
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+#define DEBUG
+#ifdef DEBUG
+ #define DEBUG_PRINT(x) pc.printf(x) //Serial.print(x)
+ #define DEBUG_PRINTF(x, y) pc.printf(x,y) //Serial.print(x, y)
+//#define DEBUG_PRINTLN(x) Serial.println(x)
+//#define DEBUG_PRINTLNF(x, y) Serial.println(x, y)
+#else
+#define DEBUG_PRINT(x)
+#define DEBUG_PRINTF(x, y)
+//#define DEBUG_PRINTLN(x)
+//#define DEBUG_PRINTLNF(x, y)
+#endif
+
+#define MPU6050_DMP_CODE_SIZE 1962 // dmpMemory[]
+#define MPU6050_DMP_CONFIG_SIZE 232 // dmpConfig[]
+#define MPU6050_DMP_UPDATES_SIZE 140 // dmpUpdates[]
+
+/* ================================================================================================ *
+| Default MotionApps v4.1 48-byte FIFO packet structure: |
+| |
+| [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] |
+| 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 |
+| |
+| [GYRO Z][ ][MAG X ][MAG Y ][MAG Z ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] |
+| 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 |
+* ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+const prog_uchar dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
+ // bank 0, 256 bytes
+ 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+ 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+ 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+ 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+ 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+ 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+ 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+ 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+ // bank 1, 256 bytes
+ 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+ 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+ 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+ 0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+
+ // bank 2, 256 bytes
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x78, 0xA2,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+ // bank 3, 256 bytes
+ 0xD8, 0xDC, 0xF4, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xF1, 0xBA, 0xA2, 0xDE, 0xB2, 0xB8, 0xB4,
+ 0xA8, 0x81, 0x98, 0xF7, 0x4A, 0x90, 0x7F, 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA,
+ 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80,
+ 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0,
+ 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1,
+ 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3,
+ 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88,
+ 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF,
+ 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89,
+ 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9,
+ 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A,
+ 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11,
+ 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55,
+ 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xBA, 0xAD, 0x8F, 0x9F, 0x28, 0x54,
+ 0x7C, 0xB9, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xDB, 0xB2, 0xB6, 0x8E, 0x9D,
+ 0xAE, 0xF5, 0x60, 0x68, 0x70, 0xB1, 0xB5, 0xF1, 0xDA, 0xA6, 0xDF, 0xD9, 0xA6, 0xFA, 0xA3, 0x86,
+
+ // bank 4, 256 bytes
+ 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+ 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+ 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+ 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+ 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+ 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+ 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+ 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+ 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+ 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+ 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+ 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+ 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+ 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+
+ // bank 5, 256 bytes
+ 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+ 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+ 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+ 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+ 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+ 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+ 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+ 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+ 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+ 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+ 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0x97, 0x86,
+ 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40,
+ 0xB9, 0xA3, 0x8A, 0xC3, 0xC5, 0xC7, 0x9A, 0xA3, 0x28, 0x50, 0x78, 0xF1, 0xB5, 0x93, 0x01, 0xD9,
+ 0xDF, 0xDF, 0xDF, 0xD8, 0xB8, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, 0x28, 0x51, 0x79, 0x1D, 0x30,
+ 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, 0x78, 0x9B, 0xF1, 0x1A, 0xB0,
+ 0xF0, 0xB1, 0x83, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0xB0, 0x8B, 0x29, 0x51, 0x79, 0xB1, 0x83, 0x24,
+
+ // bank 6, 256 bytes
+ 0x70, 0x59, 0xB0, 0x8B, 0x20, 0x58, 0x71, 0xB1, 0x83, 0x44, 0x69, 0x38, 0xB0, 0x8B, 0x39, 0x40,
+ 0x68, 0xB1, 0x83, 0x64, 0x48, 0x31, 0xB0, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71,
+ 0x58, 0x44, 0x68, 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0,
+ 0x8C, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02,
+ 0x26, 0x46, 0x66, 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38,
+ 0x64, 0x48, 0x31, 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19,
+ 0x31, 0x48, 0x60, 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86,
+ 0xA8, 0x6E, 0x76, 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A,
+ 0x6E, 0x8A, 0x56, 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E,
+ 0x9D, 0xB8, 0xAD, 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55,
+ 0x7D, 0x81, 0x91, 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D,
+ 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51,
+ 0xD9, 0x04, 0xAE, 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19,
+ 0x81, 0xAD, 0xD9, 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9,
+ 0xAD, 0xAD, 0xAD, 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76,
+ 0xF3, 0xAC, 0x2E, 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC,
+
+ // bank 7, 170 bytes (remainder)
+ 0x30, 0x18, 0xA8, 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24,
+ 0xF2, 0xB0, 0x89, 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9,
+ 0xD8, 0xD8, 0x79, 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D,
+ 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D,
+ 0x80, 0x25, 0xDA, 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34,
+ 0x3C, 0xF3, 0xAB, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0, 0x87, 0x9C, 0xB9,
+ 0xA3, 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3,
+ 0xA3, 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+ 0xA3, 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3,
+ 0xA3, 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3,
+ 0xDC, 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+const prog_uchar dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
+// BANK OFFSET LENGTH [DATA]
+ 0x02, 0xEC, 0x04, 0x00, 0x47, 0x7D, 0x1A, // ?
+ 0x03, 0x82, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration
+ 0x03, 0xB2, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration
+ 0x00, 0x68, 0x04, 0x02, 0xCA, 0xE3, 0x09, // D_0_104 inv_set_gyro_calibration
+ 0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration
+ 0x03, 0x86, 0x03, 0x0C, 0xC9, 0x2C, // FCFG_2 inv_set_accel_calibration
+ 0x03, 0x90, 0x03, 0x26, 0x46, 0x66, // (continued)...FCFG_2 inv_set_accel_calibration
+ 0x00, 0x6C, 0x02, 0x40, 0x00, // D_0_108 inv_set_accel_calibration
+
+ 0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration
+ 0x02, 0x44, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_01
+ 0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02
+ 0x02, 0x4C, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_10
+ 0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11
+ 0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12
+ 0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20
+ 0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21
+ 0x02, 0xBC, 0x04, 0xC0, 0x00, 0x00, 0x00, // CPASS_MTX_22
+
+ 0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel
+ 0x03, 0x86, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+ 0x04, 0x22, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+ 0x00, 0xA3, 0x01, 0x00, // ?
+ 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+ 0x07, 0x9F, 0x01, 0x30, // CFG_16 inv_set_footer
+ 0x07, 0x67, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro
+ 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+ 0x02, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // ?
+ 0x07, 0x83, 0x06, 0xC2, 0xCA, 0xC4, 0xA3, 0xA3, 0xA3, // ?
+ // SPECIAL 0x01 = enable interrupts
+ 0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE, SPECIAL INSTRUCTION
+ 0x07, 0xA7, 0x01, 0xFE, // ?
+ 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+ 0x07, 0x67, 0x01, 0x9A, // ?
+ 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo
+ 0x07, 0x8D, 0x04, 0xF1, 0x28, 0x30, 0x38, // ??? CFG_12 inv_send_mag -> inv_construct3_fifo
+ 0x02, 0x16, 0x02, 0x00, 0x03 // D_0_22 inv_set_fifo_rate
+
+ // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+ // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+ // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+ // It is important to make sure the host processor can keep up with reading and processing
+ // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const prog_uchar dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
+ 0x01, 0xB2, 0x02, 0xFF, 0xF5,
+ 0x01, 0x90, 0x04, 0x0A, 0x0D, 0x97, 0xC0,
+ 0x00, 0xA3, 0x01, 0x00,
+ 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D,
+ 0x01, 0x6A, 0x02, 0x06, 0x00,
+ 0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
+ 0x02, 0x60, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x01, 0x08, 0x02, 0x01, 0x20,
+ 0x01, 0x0A, 0x02, 0x00, 0x4E,
+ 0x01, 0x02, 0x02, 0xFE, 0xB3,
+ 0x02, 0x6C, 0x04, 0x00, 0x00, 0x00, 0x00, // READ
+ 0x02, 0x6C, 0x04, 0xFA, 0xFE, 0x00, 0x00,
+ 0x02, 0x60, 0x0C, 0xFF, 0xFF, 0xCB, 0x4D, 0x00, 0x01, 0x08, 0xC1, 0xFF, 0xFF, 0xBC, 0x2C,
+ 0x02, 0xF4, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x02, 0xF8, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x02, 0xFC, 0x04, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
+ 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00
+};
+
+uint8_t MPU6050::dmpInitialize() {
+ Serial pc(USBTX, USBRX); // tx, rx
+ pc.baud(115200);
+ wait_ms(50);
+
+ pc.printf("\n\nSet USB Baudrate to 115200...\n");
+
+ // reset device
+ DEBUG_PRINT("\n\nResetting MPU6050...");
+ reset();
+ wait_ms(30);
+
+ // disable sleep mode
+ DEBUG_PRINT("Disabling sleep mode...");
+ setSleepEnabled(false);
+
+ // get MPU product ID
+// DEBUG_PRINT("Getting product ID...");
+// uint8_t productID = 0;
+// getProductID();
+// DEBUG_PRINT("Product ID = ");
+// DEBUG_PRINTF("%u", productID);
+
+ // get MPU hardware revision
+ DEBUG_PRINT("Selecting user bank 16...\n");
+ setMemoryBank(0x10, true, true);
+ DEBUG_PRINT("Selecting memory byte 6...\n");
+ setMemoryStartAddress(0x06);
+ DEBUG_PRINT("Checking hardware revision...\n");
+ uint8_t hwRevision = readMemoryByte();
+ DEBUG_PRINT("Revision @ user[16][6] = ");
+ DEBUG_PRINTF("%x\n",hwRevision);
+ DEBUG_PRINT("Resetting memory bank selection to 0...");
+ setMemoryBank(0, false, false);
+
+ // check OTP bank valid
+ DEBUG_PRINT("Reading OTP bank valid flag...\n");
+ uint8_t otpValid = getOTPBankValid();
+ DEBUG_PRINT("OTP bank is ");
+
+ if(otpValid)DEBUG_PRINT("valid!\n");
+ else DEBUG_PRINT("invalid!\n");
+
+ // get X/Y/Z gyro offsets
+ DEBUG_PRINT("Reading gyro offset values...\n");
+ int8_t xgOffset = getXGyroOffset();
+ int8_t ygOffset = getYGyroOffset();
+ int8_t zgOffset = getZGyroOffset();
+ DEBUG_PRINT("X gyro offset = ");
+ DEBUG_PRINTF("%u\n",xgOffset);
+ DEBUG_PRINT("Y gyro offset = ");
+ DEBUG_PRINTF("%u\n",ygOffset);
+ DEBUG_PRINT("Z gyro offset = ");
+ DEBUG_PRINTF("%u\n",zgOffset);
+
+ i2Cdev.readByte(devAddr, MPU6050_RA_USER_CTRL, buffer); // ?
+
+ DEBUG_PRINT("Enabling interrupt latch, clear on any read, AUX bypass enabled\n");
+ i2Cdev.writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x32);
+
+ // enable MPU AUX I2C bypass mode
+ //DEBUG_PRINT("Enabling AUX I2C bypass mode..."));
+ //setI2CBypassEnabled(true);
+
+ DEBUG_PRINT("Setting magnetometer mode to power-down...\n");
+ //mag -> setMode(0);
+ i2Cdev.writeByte(0x0E, 0x0A, 0x00);
+
+ DEBUG_PRINT("Setting magnetometer mode to fuse access...\n");
+ //mag -> setMode(0x0F);
+ i2Cdev.writeByte(0x0E, 0x0A, 0x0F);
+
+ DEBUG_PRINT("Reading mag magnetometer factory calibration...\n");
+
+ int8_t asax, asay, asaz;
+
+ //mag -> getAdjustment(&asax, &asay, &asaz);
+
+ i2Cdev.readBytes(0x0E, 0x10, 3, buffer);
+ asax = (int8_t)buffer[0];
+ asay = (int8_t)buffer[1];
+ asaz = (int8_t)buffer[2];
+ DEBUG_PRINT("Adjustment X/Y/Z = ");
+ DEBUG_PRINTF("%u",asax);
+ DEBUG_PRINT(" / ");
+ DEBUG_PRINTF("%u",asay);
+ DEBUG_PRINT(" / ");
+ DEBUG_PRINTF("%u\n",asaz);
+
+ DEBUG_PRINT("Setting magnetometer mode to power-down...\n");
+ //mag -> setMode(0);
+ i2Cdev.writeByte(0x0E, 0x0A, 0x00);
+
+ // load DMP code into memory banks
+ DEBUG_PRINT("Writing DMP code to MPU memory banks (");
+ DEBUG_PRINTF("%u",MPU6050_DMP_CODE_SIZE);
+ DEBUG_PRINT(" bytes)\n");
+ if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) {
+ DEBUG_PRINT("Success! DMP code written and verified.\n");
+
+ DEBUG_PRINT("Configuring DMP and related settings...\n");
+
+ // write DMP configuration
+ DEBUG_PRINT("Writing DMP configuration to MPU memory banks (");
+ DEBUG_PRINTF("%u ",MPU6050_DMP_CONFIG_SIZE);
+ DEBUG_PRINT(" bytes in config def)\n");
+ if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) {
+ DEBUG_PRINT("Success! DMP configuration written and verified.\n");
+
+ DEBUG_PRINT("Setting DMP and FIFO_OFLOW interrupts enabled...\n");
+ setIntEnabled(0x12);
+
+ DEBUG_PRINT("Setting sample rate to 200Hz...\n");
+ setRate(4); // 1khz / (1 + 4) = 200 Hz
+
+ DEBUG_PRINT("Setting clock source to Z Gyro...\n");
+ setClockSource(MPU6050_CLOCK_PLL_ZGYRO);
+
+ DEBUG_PRINT("Setting DLPF bandwidth to 42Hz...\n");
+ setDLPFMode(MPU6050_DLPF_BW_42);
+
+ DEBUG_PRINT("Setting external frame sync to TEMP_OUT_L[0]...\n");
+ setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L);
+
+ DEBUG_PRINT("Setting gyro sensitivity to +/- 2000 deg/sec...\n");
+ setFullScaleGyroRange(MPU6050_GYRO_FS_2000);
+
+ DEBUG_PRINT("Setting DMP configuration bytes (function unknown)...\n");
+ setDMPConfig1(0x03);
+ setDMPConfig2(0x00);
+
+ DEBUG_PRINT("Clearing OTP Bank flag...\n");
+ setOTPBankValid(false);
+
+ DEBUG_PRINT("Setting X/Y/Z gyro offsets to previous values...\n");
+ setXGyroOffset(xgOffset);
+ setYGyroOffset(ygOffset);
+ setZGyroOffset(zgOffset);
+
+ DEBUG_PRINT("Setting X/Y/Z gyro user offsets to zero...\n");
+ setXGyroOffsetUser(0);
+ setYGyroOffsetUser(0);
+ setZGyroOffsetUser(0);
+
+ DEBUG_PRINT("Writing final memory update 1/19 (function unknown)...\n");
+ uint8_t dmpUpdate[16],j;
+ uint16_t pos = 0;
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Writing final memory update 2/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Resetting FIFO...\n");
+ resetFIFO();
+
+ DEBUG_PRINT("Reading FIFO count...\n");
+ uint8_t fifoCount = getFIFOCount();
+
+ DEBUG_PRINT("Current FIFO count=");
+ DEBUG_PRINTF("%u\n",fifoCount);
+ uint8_t fifoBuffer[128];
+ getFIFOBytes(fifoBuffer, fifoCount);
+
+ DEBUG_PRINT("Writing final memory update 3/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Writing final memory update 4/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Disabling all standby flags...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_PWR_MGMT_2, 0x00);
+
+ DEBUG_PRINT("Setting accelerometer sensitivity to +/- 2g...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_ACCEL_CONFIG, 0x00);
+
+ DEBUG_PRINT("Setting motion detection threshold to 2...\n");
+ setMotionDetectionThreshold(2);
+
+ DEBUG_PRINT("Setting zero-motion detection threshold to 156...\n");
+ setZeroMotionDetectionThreshold(156);
+
+ DEBUG_PRINT("Setting motion detection duration to 80...\n");
+ setMotionDetectionDuration(80);
+
+ DEBUG_PRINT("Setting zero-motion detection duration to 0...\n");
+ setZeroMotionDetectionDuration(0);
+
+ DEBUG_PRINT("Setting AK8975 to single measurement mode...\n");
+ //mag -> setMode(1);
+ i2Cdev.writeByte(0x0E, 0x0A, 0x01);
+
+ // setup AK8975 (0x0E) as Slave 0 in read mode
+ DEBUG_PRINT("Setting up AK8975 read slave 0...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV0_ADDR, 0x8E);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV0_REG, 0x01);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV0_CTRL, 0xDA);
+
+ // setup AK8975 (0x0E) as Slave 2 in write mode
+ DEBUG_PRINT("Setting up AK8975 write slave 2...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV2_ADDR, 0x0E);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV2_REG, 0x0A);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV2_CTRL, 0x81);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV2_DO, 0x01);
+
+ // setup I2C timing/delay control
+ DEBUG_PRINT("Setting up slave access delay...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_SLV4_CTRL, 0x18);
+ i2Cdev.writeByte(0x68, MPU6050_RA_I2C_MST_DELAY_CTRL, 0x05);
+
+ // enable interrupts
+ DEBUG_PRINT("Enabling default interrupt behavior/no bypass...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_INT_PIN_CFG, 0x00);
+
+ // enable I2C master mode and reset DMP/FIFO
+ DEBUG_PRINT("Enabling I2C master mode...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20);
+ DEBUG_PRINT("Resetting FIFO...");
+ i2Cdev.writeByte(0x68, MPU6050_RA_USER_CTRL, 0x24);
+ DEBUG_PRINT("Rewriting I2C master mode enabled because...I don't know\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20);
+ DEBUG_PRINT("Enabling and resetting DMP/FIFO...\n");
+ i2Cdev.writeByte(0x68, MPU6050_RA_USER_CTRL, 0xE8);
+
+ DEBUG_PRINT("Writing final memory update 5/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 6/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 7/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 8/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 9/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 10/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 11/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Reading final memory update 12/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+#ifdef DEBUG
+ DEBUG_PRINT("Read bytes: ");
+ for (j = 0; j < 4; j++) {
+ DEBUG_PRINTF("%u",dmpUpdate[3 + j]);
+ DEBUG_PRINT("\n");
+ }
+ DEBUG_PRINT("\n");
+#endif
+
+ DEBUG_PRINT("Writing final memory update 13/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 14/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 15/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 16/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+ DEBUG_PRINT("Writing final memory update 17/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Waiting for FIFO count >= 46...\n");
+ while ((fifoCount = getFIFOCount()) < 46);
+ DEBUG_PRINT("Reading FIFO...\n");
+ getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+ DEBUG_PRINT("Reading interrupt status...\n");
+ getIntStatus();
+
+ DEBUG_PRINT("Writing final memory update 18/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Waiting for FIRO count >= 48...\n");
+ while ((fifoCount = getFIFOCount()) < 48);
+ DEBUG_PRINT("Reading FIFO...");
+ getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+ DEBUG_PRINT("Reading interrupt status...\n");
+ getIntStatus();
+ DEBUG_PRINT("Waiting for FIRO count >= 48...\n");
+ while ((fifoCount = getFIFOCount()) < 48);
+ DEBUG_PRINT("Reading FIFO...\n");
+ getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+ DEBUG_PRINT("Reading interrupt status...\n");
+ getIntStatus();
+
+ DEBUG_PRINT("Writing final memory update 19/19 (function unknown)...\n");
+ for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+ writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+ DEBUG_PRINT("Disabling DMP (you turn it on later)...\n");
+ setDMPEnabled(false);
+
+ DEBUG_PRINT("Setting up internal 48-byte (default) DMP packet buffer...\n");
+ dmpPacketSize = 48;
+ /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+return 3; // TODO: proper error code for no memory
+}*/
+
+ DEBUG_PRINT("Resetting FIFO and clearing INT status one last time...\n");
+ resetFIFO();
+ getIntStatus();
+ } else {
+ DEBUG_PRINT("ERROR! DMP configuration verification failed.\n");
+ return 2; // configuration block loading failed
+ }
+ } else {
+ DEBUG_PRINT("ERROR! DMP code verification failed.\n");
+ return 1; // main binary block loading failed
+ }
+ return 0; // success
+}
+
+bool MPU6050::dmpPacketAvailable() {
+ return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU6050::dmpGetFIFORate();
+// uint8_t MPU6050::dmpGetSampleStepSizeMS();
+// uint8_t MPU6050::dmpGetSampleFrequency();
+// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU6050::dmpRunFIFORateProcesses();
+
+// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[34] << 24) + (packet[35] << 16) + (packet[36] << 8) + packet[37]);
+ data[1] = ((packet[38] << 24) + (packet[39] << 16) + (packet[40] << 8) + packet[41]);
+ data[2] = ((packet[42] << 24) + (packet[43] << 16) + (packet[44] << 8) + packet[45]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[34] << 8) + packet[35];
+ data[1] = (packet[38] << 8) + packet[39];
+ data[2] = (packet[42] << 8) + packet[43];
+ return 0;
+}
+uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ v -> x = (packet[34] << 8) + packet[35];
+ v -> y = (packet[38] << 8) + packet[39];
+ v -> z = (packet[42] << 8) + packet[43];
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 24) + (packet[1] << 16) + (packet[2] << 8) + packet[3]);
+ data[1] = ((packet[4] << 24) + (packet[5] << 16) + (packet[6] << 8) + packet[7]);
+ data[2] = ((packet[8] << 24) + (packet[9] << 16) + (packet[10] << 8) + packet[11]);
+ data[3] = ((packet[12] << 24) + (packet[13] << 16) + (packet[14] << 8) + packet[15]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[0] << 8) + packet[1]);
+ data[1] = ((packet[4] << 8) + packet[5]);
+ data[2] = ((packet[8] << 8) + packet[9]);
+ data[3] = ((packet[12] << 8) + packet[13]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ int16_t qI[4];
+ uint8_t status = dmpGetQuaternion(qI, packet);
+ if (status == 0) {
+ q -> w = (float)qI[0] / 16384.0f;
+ q -> x = (float)qI[1] / 16384.0f;
+ q -> y = (float)qI[2] / 16384.0f;
+ q -> z = (float)qI[3] / 16384.0f;
+ return 0;
+ }
+ return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = ((packet[16] << 24) + (packet[17] << 16) + (packet[18] << 8) + packet[19]);
+ data[1] = ((packet[20] << 24) + (packet[21] << 16) + (packet[22] << 8) + packet[23]);
+ data[2] = ((packet[24] << 24) + (packet[25] << 16) + (packet[26] << 8) + packet[27]);
+ return 0;
+}
+uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[16] << 8) + packet[17];
+ data[1] = (packet[20] << 8) + packet[21];
+ data[2] = (packet[24] << 8) + packet[25];
+ return 0;
+}
+uint8_t MPU6050::dmpGetMag(int16_t *data, const uint8_t* packet) {
+ // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+ if (packet == 0) packet = dmpPacketBuffer;
+ data[0] = (packet[28] << 8) + packet[29];
+ data[1] = (packet[30] << 8) + packet[31];
+ data[2] = (packet[32] << 8) + packet[33];
+ return 0;
+}
+// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+ // get rid of the gravity component (+1g = +4096 in standard DMP FIFO packet)
+ v -> x = vRaw -> x - gravity -> x*4096;
+ v -> y = vRaw -> y - gravity -> y*4096;
+ v -> z = vRaw -> z - gravity -> z*4096;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+ // rotate measured 3D acceleration vector into original state
+ // frame of reference based on orientation quaternion
+ memcpy(v, vReal, sizeof(VectorInt16));
+ v -> rotate(q);
+ return 0;
+}
+// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+ v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+ v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+ v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+ return 0;
+}
+// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q) {
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi
+ data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta
+ data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi
+ return 0;
+}
+uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+ // yaw: (about Z axis)
+ data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+ // pitch: (nose up/down, about Y axis)
+ data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+ // roll: (tilt left/right, about X axis)
+ data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+ return 0;
+}
+
+// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+ /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+if (dmpData[k] < 0x10) Serial.print("0");
+Serial.print(dmpData[k], HEX);
+Serial.print(" ");
+}
+Serial.print("\n");*/
+ //Serial.println((uint16_t)dmpPacketBuffer);
+ return 0;
+}
+uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+ uint8_t status;
+ uint8_t buf[dmpPacketSize];
+ for (uint8_t i = 0; i < numPackets; i++) {
+ // read packet from FIFO
+ getFIFOBytes(buf, dmpPacketSize);
+
+ // process packet
+ if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+
+ // increment external process count variable, if supplied
+ if (processed != 0) *processed++;
+ }
+ return 0;
+}
+
+// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU6050::dmpInitFIFOParam();
+// uint8_t MPU6050::dmpCloseFIFO();
+// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU6050::dmpDecodeQuantizedAccel();
+// uint32_t MPU6050::dmpGetGyroSumOfSquare();
+// uint32_t MPU6050::dmpGetAccelSumOfSquare();
+// void MPU6050::dmpOverrideQuaternion(long *q);
+uint16_t MPU6050::dmpGetFIFOPacketSize() {
+ return dmpPacketSize;
+}
+
+#endif /* _MPU6050_9AXIS_MOTIONAPPS41_H_ */
diff -r 000000000000 -r e63996fd7d3e PIDTheta.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PIDTheta.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,92 @@
+#ifndef _MBED_H
+#define _MBED_H
+#include "mbed.h"
+#endif
+#include "PIDTheta.h"
+#define Error_operation_limits 0.25
+#define sigmoid_fun(h) (2/(1+exp(-h)))-1
+#define NULLAREA 0.015
+//constructor
+PIDTheta::PIDTheta( PinName pwm,PinName pwm2,float Listen_time_ms,float KP,float KI,float KD,float KDD ): _pwm(pwm),_pwm2(pwm2)/*, debugSerial(USBTX, USBRX)*/
+{
+ //debugSerial.baud(D_BAUDRATE);
+ Motor_init(Listen_time_ms);
+ _pwm = 0;
+ _pwm2 = 0;
+ Out_PWM=0.001;
+ Out_PWM2=0.001;
+ _KP=KP;
+ _KD=KD;
+ _KI=KI;
+ _KDD=KDD;
+ h=0;
+ ErrorDD=0;
+ ErrorD=0;
+ //debugSerial.printf("\r\n\r\n\r\nhere\r\n");
+ Motor_Control_signal();
+ PowerSetPoint=0.001;
+}
+void PIDTheta::Motor_init(float Listen_time_ms)
+{
+ _pwm.period_ms(Listen_time_ms);
+ _pwm2.period_ms(Listen_time_ms);
+}
+void PIDTheta::Motor_Control_signal()
+{
+ //debugSerial.printf("\r\n\r\n\r\n1:%f 2:%f\r\n",Out_PWM,Out_PWM2);
+
+ _pwm.pulsewidth(Out_PWM);
+ _pwm2.pulsewidth(Out_PWM2);
+}
+void PIDTheta::PWM_cal(float Theta_req,float Theta_curr,float req_power_SP)
+{
+ PowerSetPoint=req_power_SP;
+
+ //debugSerial.printf("\r\nthetareq:%f thetacurr:%f\r\n",Theta_req,Theta_curr);
+
+ Check_IN_Limits(&Theta_req);
+ Pulse_Error_cal(Theta_req,Theta_curr);
+
+ Out_PWM= PowerSetPoint-h;
+ Out_PWM2= PowerSetPoint+h;
+ Check_OUT_Limits(&Out_PWM);
+ Check_OUT_Limits(&Out_PWM2);
+ Motor_Control_signal();
+}
+//error calculating and out the relative output to the relative error.
+void PIDTheta::Pulse_Error_cal(float RPM_req,float RPM_curr)
+{
+ //debugSerial.printf("req:%f curr:%f",RPM_req,RPM_curr);
+ Error=RPM_req-RPM_curr;
+ ErrorI=ErrorI+Error;
+ ErrorD=Error-ErrorOLD;
+ ErrorOLD=Error;
+ ErrorDD=ErrorD-ErrorDOLD;
+ ErrorDOLD=ErrorD;
+ h=_KP*Error+_KI*ErrorI+_KD*ErrorD+_KDD*ErrorDD;
+
+}
+//setting Output Limits.
+void PIDTheta::Set_OUT_Limits(float LowerLimt,float UpperLimit)
+{
+ O_Upper_Limit=UpperLimit;
+ O_Lower_Limit=LowerLimt;
+}
+//setting Input Limits.
+void PIDTheta::Set_IN_Limits(float LowerLimit,float UpperLimit)
+{
+ I_Upper_Limit=UpperLimit;
+ I_Lower_Limit=LowerLimit;
+}
+//checking Input Limits in the Realtime operation.
+void PIDTheta::Check_OUT_Limits(float *RPMSetPoint)
+{
+ if(*RPMSetPoint>O_Upper_Limit)*RPMSetPoint=O_Upper_Limit;
+ if(*RPMSetPoint<O_Lower_Limit)*RPMSetPoint=O_Lower_Limit;
+}
+//checking Output Limits in Realtime operation.
+void PIDTheta::Check_IN_Limits(float *O_PWM)
+{
+ if(*O_PWM>I_Upper_Limit)*O_PWM=I_Upper_Limit;
+ if(*O_PWM<I_Lower_Limit)*O_PWM=I_Lower_Limit;
+}
diff -r 000000000000 -r e63996fd7d3e PIDTheta.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PIDTheta.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,44 @@
+//Includes//
+#ifndef _QuadCopter_H
+#define _QuadCopter_H
+#ifndef _MBED_H
+#define _MBED_H
+#include "mbed.h"
+#endif
+#ifndef _IOSTREAM_
+#define _IOSTREAM_
+#include "iostream"
+#endif
+#ifndef _MATH_H
+#define _MATH_H
+#define D_BAUDRATE 115200
+//#include "math.h"
+#endif
+class PIDTheta{
+ public:
+ PIDTheta( PinName pwm,PinName pwm2,float Listen_time_ms,float KP,float KI,float KD,float KDD);//constructor
+ void Motor_init(float Listen_time_ms);//initialization motors
+ void Motor_Control_signal();//giving control signal to the motor.
+
+ void PWM_cal(float RPM_req,float RPM_curr,float req_power_SP);//calculating the PWM taking in mind upper/lower limits and error calculation/estimation.
+ void Set_OUT_Limits(float LowerLimit,float UpperLimit);//setting Output Limits.
+ void Set_IN_Limits(float LowerLimit,float UpperLimit);//setting Input Limits.
+ void Check_OUT_Limits(float *RPMSetPoint);//checking Input Limits in the Realtime operation.
+ void Check_IN_Limits(float *O_PWM);//checking Output Limits in Realtime operation.
+
+ private:
+ void Pulse_Error_cal(float RPM_req,float RPM_curr);//error calculating and out the relative output to the relative error.
+ //variables and PinRoles
+ float PowerSetPoint;//,RPMSetPoint;
+ float Out_PWM,Out_PWM2;
+ float O_Upper_Limit,O_Lower_Limit;
+ float I_Upper_Limit,I_Lower_Limit;
+ float Error,ErrorI,ErrorD,ErrorOLD,ErrorDD,ErrorDOLD;
+ float h;
+ float _KP,_KD,_KI,_KDD;
+ //Serial debugSerial;
+ PwmOut _pwm;
+ PwmOut _pwm2;
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e PID_Alt.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PID_Alt.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,149 @@
+#ifndef _PID_Alt
+#define _PID_Alt
+#include "SHARPIR.h"
+#include "mbed.h"
+#define D_BAUDRATE 115200
+
+class PID_Alt{
+ public:
+ PID_Alt(int Mnum,float KP,float KI,float KD,float KDD,PinName AnalogPort);
+ float findNominalVal(float altitude,float CosR,float CosP,char Calibrated);
+ void Set_OUT_Limits(float LowerLimit,float UpperLimit);//setting Output Limits.
+ void Set_IN_Limits(float LowerLimit,float UpperLimit);//setting Input Limits.
+ void Check_OUT_Limits(float *RPMSetPoint);//checking Input Limits in the Realtime operation.
+ void Check_IN_Limits(float *O_PWM);//checking Output Limits in Realtime operation.
+ float Get_IR_Readings();
+ float Get_OUT_POWER_SP();
+ float Get_Current_IR();
+ float GetErrorV();
+ float GetErrorVD();
+ float GetErrorVDD();
+ float GetErrorVDOLD();
+ float Get_reqestedAlt();
+
+ float MeanIR(int num);
+ private:
+ SHARPIR _IR;
+ float PowerSetPoint;//,RPMSetPoint;
+ float Out_PWM,Out_PWM2;
+ float O_Upper_Limit,O_Lower_Limit;
+ float I_Upper_Limit,I_Lower_Limit;
+ float ErrorV,ErrorI,ErrorVD,ErrorVold,ErrorVDD,ErrorVDOLD,altitudeOld,nominalVal2;
+ float V_req,V_curr,CURRENT_Alt;
+ float h;
+ float EVDOLDGetter,reqestedAlt;
+ float _KP,_KD,_KI,_KDD;
+ int Meannum;
+ Serial debugSerial;
+
+ };
+PID_Alt::PID_Alt(int Mnum,float KP,float KI,float KD,float KDD,PinName AnalogPort):_IR(AnalogPort), debugSerial(USBTX, USBRX){
+ _KP=KP;
+ _KD=KD;
+ _KI=KI;
+ _KDD=KDD;
+ Meannum=Mnum;
+ V_req=0;
+ V_curr=0;
+ ErrorV=0;
+ ErrorI=0;
+ ErrorVD=0;
+ ErrorVold=0;
+ ErrorVDD=0;
+ ErrorVDOLD=0;
+ altitudeOld=0;
+ nominalVal2=0.00115;
+ debugSerial.baud(D_BAUDRATE);
+
+
+ }
+float PID_Alt::findNominalVal(float altitude,float CosR,float CosP,char Calibrated){
+ float curr_alt=0;
+ Check_IN_Limits(&altitude);
+ reqestedAlt=altitude;
+ curr_alt=MeanIR(Meannum)*CosR*CosP;
+ if(curr_alt<=9){
+ curr_alt=150;
+ }
+ CURRENT_Alt=curr_alt;
+ Check_IN_Limits(&curr_alt);
+ V_req=altitude-curr_alt;
+ V_curr=curr_alt-altitudeOld;
+ altitudeOld=curr_alt;
+ ErrorV= V_curr-V_req;
+ ErrorVD= ErrorV-ErrorVold;
+ ErrorVDD=ErrorVD-ErrorVDOLD;
+ EVDOLDGetter=ErrorVDOLD;
+ debugSerial.printf("E:%f ED:%f EDD:%f EDOld:%f\r\n",ErrorV,ErrorVD,ErrorVDD,ErrorVDOLD);
+ if(Calibrated)
+ nominalVal2=nominalVal2-_KP*ErrorV-_KD*ErrorVD-_KDD*ErrorVDD;
+ ErrorVold=ErrorV;
+ ErrorVDOLD=ErrorVD;
+
+ //debugSerial.printf("error:%f aError:%f alt:%f NV:%f Real:%f\r\n",(MeanIR(Meannum)-altitude), alpha*(MeanIR(Meannum)-altitude),altitude,nominalVal2,MeanIR(Meannum));
+ Check_OUT_Limits(&nominalVal2);
+ return nominalVal2;
+ }
+float PID_Alt::MeanIR(int num)
+{
+ float MeanReading=0;
+ for(int i=0;i<num;i++)MeanReading+=Get_IR_Readings();
+ return MeanReading/num;
+}
+float PID_Alt::Get_reqestedAlt(){
+ return reqestedAlt;
+ }
+float PID_Alt::GetErrorVDOLD(){
+ return EVDOLDGetter;
+ }
+float PID_Alt::GetErrorV(){
+ return ErrorV;
+ }
+float PID_Alt::GetErrorVD(){
+ return ErrorVD;
+ }
+float PID_Alt::GetErrorVDD(){
+ return ErrorVDD;
+ }
+float PID_Alt::Get_OUT_POWER_SP()
+{
+ return nominalVal2;
+}
+float PID_Alt::Get_IR_Readings()
+{
+ return _IR.cm();
+}
+float PID_Alt::Get_Current_IR()
+{
+ return CURRENT_Alt;
+}
+//setting Output Limits.
+void PID_Alt::Set_OUT_Limits(float LowerLimt,float UpperLimit)
+{
+ O_Upper_Limit=UpperLimit;
+ O_Lower_Limit=LowerLimt;
+ //initializations
+ // power=O_Lower_Limit;
+ // prev_power=O_Lower_Limit;
+}
+//setting Input Limits.
+void PID_Alt::Set_IN_Limits(float LowerLimit,float UpperLimit)
+{
+ I_Upper_Limit=UpperLimit;
+ I_Lower_Limit=LowerLimit;
+ // prev_alt=I_Lower_Limit;
+}
+//checking Input Limits in the Realtime operation.
+void PID_Alt::Check_OUT_Limits(float *RPMSetPoint)
+{
+ if(*RPMSetPoint>O_Upper_Limit)*RPMSetPoint=O_Upper_Limit;
+ if(*RPMSetPoint<O_Lower_Limit)*RPMSetPoint=O_Lower_Limit;
+}
+//checking Output Limits in Realtime operation.
+void PID_Alt::Check_IN_Limits(float *O_PWM)
+{
+ if(*O_PWM>I_Upper_Limit)*O_PWM=I_Upper_Limit;
+ if(*O_PWM<I_Lower_Limit)*O_PWM=I_Lower_Limit;
+}
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e PID_Yaw.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PID_Yaw.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,77 @@
+#ifndef _MBED_H
+#define _MBED_H
+#include "mbed.h"
+#endif
+#include "PID_Yaw.h"
+#define Error_operation_limits 0.25
+#define sigmoid_fun(h) (2/(1+exp(-h)))-1
+#define NULLAREA 0.015
+//constructor
+PID_Yaw::PID_Yaw(float KP,float KI,float KD,float KDD ) /*, debugSerial(USBTX, USBRX)*/
+{
+ //debugSerial.baud(D_BAUDRATE);
+ Out_PWM=0.001;
+ Out_PWM2=0.001;
+ _KP=KP;
+ _KD=KD;
+ _KI=KI;
+ _KDD=KDD;
+ h=0;
+ ErrorDD=0;
+ ErrorD=0;
+ //debugSerial.printf("\r\n\r\n\r\nhere\r\n");
+ PowerSetPoint=0.001;
+}
+void PID_Yaw::PWM_cal(float Theta_req,float Theta_curr,float req_power_SP,float * xPlanePWM,float *yPlanePWM )
+{
+ PowerSetPoint=req_power_SP;
+
+ //debugSerial.printf("\r\nthetareq:%f thetacurr:%f\r\n",Theta_req,Theta_curr);
+
+ Check_IN_Limits(&Theta_req);
+ Pulse_Error_cal(Theta_req,Theta_curr);
+
+ Out_PWM= PowerSetPoint-h;
+ Out_PWM2= PowerSetPoint+h;
+ Check_OUT_Limits(&Out_PWM);
+ Check_OUT_Limits(&Out_PWM2);
+ *xPlanePWM=Out_PWM;
+ *yPlanePWM=Out_PWM2;
+}
+//error calculating and out the relative output to the relative error.
+void PID_Yaw::Pulse_Error_cal(float RPM_req,float RPM_curr)
+{
+ //debugSerial.printf("req:%f curr:%f",RPM_req,RPM_curr);
+ Error=RPM_req-RPM_curr;
+ ErrorI=ErrorI+Error;
+ ErrorD=Error-ErrorOLD;
+ ErrorOLD=Error;
+ ErrorDD=ErrorD-ErrorDOLD;
+ ErrorDOLD=ErrorD;
+ h=_KP*Error+_KI*ErrorI+_KD*ErrorD+_KDD*ErrorDD;
+
+}
+//setting Output Limits.
+void PID_Yaw::Set_OUT_Limits(float LowerLimt,float UpperLimit)
+{
+ O_Upper_Limit=UpperLimit;
+ O_Lower_Limit=LowerLimt;
+}
+//setting Input Limits.
+void PID_Yaw::Set_IN_Limits(float LowerLimit,float UpperLimit)
+{
+ I_Upper_Limit=UpperLimit;
+ I_Lower_Limit=LowerLimit;
+}
+//checking Input Limits in the Realtime operation.
+void PID_Yaw::Check_OUT_Limits(float *RPMSetPoint)
+{
+ if(*RPMSetPoint>O_Upper_Limit)*RPMSetPoint=O_Upper_Limit;
+ if(*RPMSetPoint<O_Lower_Limit)*RPMSetPoint=O_Lower_Limit;
+}
+//checking Output Limits in Realtime operation.
+void PID_Yaw::Check_IN_Limits(float *O_PWM)
+{
+ if(*O_PWM>I_Upper_Limit)*O_PWM=I_Upper_Limit;
+ if(*O_PWM<I_Lower_Limit)*O_PWM=I_Lower_Limit;
+}
diff -r 000000000000 -r e63996fd7d3e PID_Yaw.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/PID_Yaw.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,41 @@
+//Includes//
+#ifndef _QuadCopter_H_yaw
+#define _QuadCopter_H_yaw
+#ifndef _MBED_H
+#define _MBED_H
+#include "mbed.h"
+#endif
+#ifndef _IOSTREAM_
+#define _IOSTREAM_
+#include "iostream"
+#endif
+#ifndef _MATH_H
+#define _MATH_H
+#define D_BAUDRATE 115200
+//#include "math.h"
+#endif
+class PID_Yaw{
+ public:
+ PID_Yaw(float KP,float KI,float KD,float KDD);//constructor
+
+ void PWM_cal(float RPM_req,float RPM_curr,float req_power_SP,float * xPlanePWM,float *yPlanePWM );//calculating the PWM taking in mind upper/lower limits and error calculation/estimation.
+ void Set_OUT_Limits(float LowerLimit,float UpperLimit);//setting Output Limits.
+ void Set_IN_Limits(float LowerLimit,float UpperLimit);//setting Input Limits.
+ void Check_OUT_Limits(float *RPMSetPoint);//checking Input Limits in the Realtime operation.
+ void Check_IN_Limits(float *O_PWM);//checking Output Limits in Realtime operation.
+
+ private:
+ void Pulse_Error_cal(float RPM_req,float RPM_curr);//error calculating and out the relative output to the relative error.
+ //variables and PinRoles
+ float PowerSetPoint;//,RPMSetPoint;
+ float Out_PWM,Out_PWM2;
+ float O_Upper_Limit,O_Lower_Limit;
+ float I_Upper_Limit,I_Lower_Limit;
+ float Error,ErrorI,ErrorD,ErrorOLD,ErrorDD,ErrorDOLD;
+ float h;
+ float _KP,_KD,_KI,_KDD;
+ //Serial debugSerial;
+
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e SHARPIR.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/SHARPIR.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,97 @@
+/* mbed SHARPIR distance sensor
+ * Copyright (c) 2010 Tomas Johansen
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+
+#include "mbed.h"
+#include "SHARPIR.h"
+
+
+/* This function is currently only working for the Sharp GP2Y0A02YK0F sensor
+ * which measures from around 20cm to 150cm. To adapt this to other Sharp IR
+ * sensors, you have to calculate the variables reg and exp.
+ *
+ * To quickly calculate reg and exp, use microsoft excel to plot the graph
+ * provided in the datasheet. You should create a scatterplot (except that
+ * the y-axis is [cm], and x-axis is [V]).
+ *
+ * When you get the values, right click the line in the graph and select
+ * "Add Trendline". Select "power". Also, in the trendline options, check
+ * that you want to see the function. It will then be printed in your
+ * scatterplot.
+ *
+ * This is the function: Reg*x^exp.
+ *
+ *
+ * Example:
+ *
+ * SHARPIR sensor(p20);
+ * sensor.calibrate(57.373, 1.3166, 0.45, 2.5);
+ * while(1){
+ * serial.printf("cm: %f ", sensor.cm());
+ * wait_ms(50);
+ * }
+ *
+ * You can also use this method to manually plot values you've measured with
+ * the "volt" function, which in the end should give a result similar to the
+ * values provided below.
+ *
+ * Feel free to contact me with improvements for the source code, and
+ * especially for values that would work for other sensors.
+ */
+
+
+SHARPIR::SHARPIR(PinName AnalogPort)
+ : _analogin(AnalogPort) {
+ higherrange=2.5;
+ lowerrange=0.45;
+ reg=57.373; //60.495
+ exp=-1.3166; //-1.1904
+}
+
+void calibrate(double reg, float exp, double lowerrange, double higherrange) { //sets new reg and exp value
+}
+
+float SHARPIR::volt() {
+ return(_analogin.read()*3.3); //analogin function returns a percentage which describes how much of 3.3v it's reading, therefor multiply it by 3,3 to get the correct analogin voltage.
+}
+
+float SHARPIR::cm() {
+ float v;
+ v=volt();
+ if (v>higherrange) //sensor is out of higher range
+ return(reg*pow(v, exp));//0
+ else if (v<lowerrange)
+ return(-1.0); //sensor is out of lower range
+ else
+ return(reg*pow(v, exp));
+}
+
+float SHARPIR::inch() {
+ float v;
+ v=volt();
+ if (v>higherrange) //sensor is out of higher range
+ return(0);
+ else if (v<lowerrange)
+ return(-1.0); //sensor is out of range
+ else
+ return(0.393700787*reg*pow(v, exp));
+}
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e SHARPIR.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/SHARPIR.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,27 @@
+/* mbed SHARPIR distance sensor
+ * Copyright (c) 2010 Tomas Johansen
+ * Released under the MIT License: http://mbed.org/license/mit
+ */
+
+#ifndef MBED_SHARPIR_H
+#define MBED_SHARPIR_H
+
+#include "mbed.h"
+
+class SHARPIR {
+public:
+ SHARPIR(PinName AnalogPort);
+ float cm();
+ float inch();
+ float volt();
+ void calibrate(double reg, float exp, double lowerrange, double higherrange);
+
+private:
+ AnalogIn _analogin;
+ double lowerrange;
+ double higherrange;
+ double reg;
+ float exp; //trendline excel + datasheet
+};
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e helper_3dmath.h
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/helper_3dmath.h Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,216 @@
+// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class, 3D math helper
+// 6/5/2012 by Jeff Rowberg <jeff@rowberg.net>
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+// 2012-06-05 - add 3D math helper file to DMP6 example sketch
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _HELPER_3DMATH_H_
+#define _HELPER_3DMATH_H_
+
+class Quaternion {
+ public:
+ float w;
+ float x;
+ float y;
+ float z;
+
+ Quaternion() {
+ w = 1.0f;
+ x = 0.0f;
+ y = 0.0f;
+ z = 0.0f;
+ }
+
+ Quaternion(float nw, float nx, float ny, float nz) {
+ w = nw;
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ Quaternion getProduct(Quaternion q) {
+ // Quaternion multiplication is defined by:
+ // (Q1 * Q2).w = (w1w2 - x1x2 - y1y2 - z1z2)
+ // (Q1 * Q2).x = (w1x2 + x1w2 + y1z2 - z1y2)
+ // (Q1 * Q2).y = (w1y2 - x1z2 + y1w2 + z1x2)
+ // (Q1 * Q2).z = (w1z2 + x1y2 - y1x2 + z1w2
+ return Quaternion(
+ w*q.w - x*q.x - y*q.y - z*q.z, // new w
+ w*q.x + x*q.w + y*q.z - z*q.y, // new x
+ w*q.y - x*q.z + y*q.w + z*q.x, // new y
+ w*q.z + x*q.y - y*q.x + z*q.w); // new z
+ }
+
+ Quaternion getConjugate() {
+ return Quaternion(w, -x, -y, -z);
+ }
+
+ float getMagnitude() {
+ return sqrt(w*w + x*x + y*y + z*z);
+ }
+
+ void normalize() {
+ float m = getMagnitude();
+ w /= m;
+ x /= m;
+ y /= m;
+ z /= m;
+ }
+
+ Quaternion getNormalized() {
+ Quaternion r(w, x, y, z);
+ r.normalize();
+ return r;
+ }
+};
+
+class VectorInt16 {
+ public:
+ int16_t x;
+ int16_t y;
+ int16_t z;
+
+ VectorInt16() {
+ x = 0;
+ y = 0;
+ z = 0;
+ }
+
+ VectorInt16(int16_t nx, int16_t ny, int16_t nz) {
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ float getMagnitude() {
+ return sqrt((float)(x*x + y*y + z*z));
+ }
+
+ void normalize() {
+ float m = getMagnitude();
+ x /= m;
+ y /= m;
+ z /= m;
+ }
+
+ VectorInt16 getNormalized() {
+ VectorInt16 r(x, y, z);
+ r.normalize();
+ return r;
+ }
+
+ void rotate(Quaternion *q) {
+ // http://www.cprogramming.com/tutorial/3d/quaternions.html
+ // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/index.htm
+ // http://content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation
+ // ^ or: http://webcache.googleusercontent.com/search?q=cache:xgJAp3bDNhQJ:content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation&hl=en&gl=us&strip=1
+
+ // P_out = q * P_in * conj(q)
+ // - P_out is the output vector
+ // - q is the orientation quaternion
+ // - P_in is the input vector (a*aReal)
+ // - conj(q) is the conjugate of the orientation quaternion (q=[w,x,y,z], q*=[w,-x,-y,-z])
+ Quaternion p(0, x, y, z);
+
+ // quaternion multiplication: q * p, stored back in p
+ p = q -> getProduct(p);
+
+ // quaternion multiplication: p * conj(q), stored back in p
+ p = p.getProduct(q -> getConjugate());
+
+ // p quaternion is now [0, x', y', z']
+ x = p.x;
+ y = p.y;
+ z = p.z;
+ }
+
+ VectorInt16 getRotated(Quaternion *q) {
+ VectorInt16 r(x, y, z);
+ r.rotate(q);
+ return r;
+ }
+};
+
+class VectorFloat {
+ public:
+ float x;
+ float y;
+ float z;
+
+ VectorFloat() {
+ x = 0;
+ y = 0;
+ z = 0;
+ }
+
+ VectorFloat(float nx, float ny, float nz) {
+ x = nx;
+ y = ny;
+ z = nz;
+ }
+
+ float getMagnitude() {
+ return sqrt(x*x + y*y + z*z);
+ }
+
+ void normalize() {
+ float m = getMagnitude();
+ x /= m;
+ y /= m;
+ z /= m;
+ }
+
+ VectorFloat getNormalized() {
+ VectorFloat r(x, y, z);
+ r.normalize();
+ return r;
+ }
+
+ void rotate(Quaternion *q) {
+ Quaternion p(0, x, y, z);
+
+ // quaternion multiplication: q * p, stored back in p
+ p = q -> getProduct(p);
+
+ // quaternion multiplication: p * conj(q), stored back in p
+ p = p.getProduct(q -> getConjugate());
+
+ // p quaternion is now [0, x', y', z']
+ x = p.x;
+ y = p.y;
+ z = p.z;
+ }
+
+ VectorFloat getRotated(Quaternion *q) {
+ VectorFloat r(x, y, z);
+ r.rotate(q);
+ return r;
+ }
+};
+
+#endif /* _HELPER_3DMATH_H_ */
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e main.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp Fri Jul 03 11:16:02 2015 +0000
@@ -0,0 +1,321 @@
+/*
+this program is to test yaw controlling plane.
+*/
+
+#include "mbed.h"
+#include "AngularDataAcquizition.h"
+//#define CascadedPID
+#include "PIDTheta.h"
+#include "PID_Alt.h"
+#include "PID_Yaw.h"
+
+#define Listen_time_ms 20
+#define ILowerRPM -3.14
+#define IUpperRPM 3.14
+#define OLowerPWM 0.001
+#define OUpperPWM 0.002
+#define OLowerPWM_yaw 0.001
+#define OUpperPWM_yaw 0.0016
+
+
+#define ILowerIR 27
+#define IUpperIR 125
+#define OLowerPower 0.00115
+#define OUpperPower 0.0018
+
+#define newILowerIR 27
+#define newIUpperIR 125
+#define newOLowerPower 0.00135
+#define newOUpperPower 0.00145
+
+
+#define KPgain 0.0000755/*0.000055 /*0.0000759*/
+#define KDgain 0.0009/*0.0007 /*0.001106*/
+#define KDDgain 0.0014/*0.0014*/
+
+#define Yaw_KP 0.0000755/*00025*/
+#define Yaw_KI 0.000
+#define Yaw_KD 0.0009/*001*/
+#define Yaw_KDD 0.0014/*0011*/
+
+
+#define Pitch_KP KPgain
+#define Pitch_KI 0.000
+#define Pitch_KD KDgain
+
+#define Roll_KP KPgain
+#define Roll_KI 0.000
+#define Roll_KD KDgain
+
+#define IR_KP 00.00000005
+#define IR_KI 0.00
+#define IR_KD 0.000001
+#define IR_KDD 0.000000
+
+#define MeanNum 5
+#define learningRate 0.00000001
+
+#define _sig_A_Kp 50
+#define _sig_A_Kd 100
+Timer t;
+//Serial pc(USBTX, USBRX);
+Serial pc(p13, p14);
+DigitalOut myled(LED1);
+LocalFileSystem local("local"); //////setting the destination of the file that will be saved
+
+AngularDataAcquizition Angle(p9, p10);
+PID_Yaw Yaw_Plane(Yaw_KP,Yaw_KI,Yaw_KD,Yaw_KDD);
+PIDTheta Pitch_Plan(p21,p23,Listen_time_ms,Pitch_KP,Pitch_KI,Pitch_KD,KDDgain);
+PIDTheta Roll_Plan(p22,p24,Listen_time_ms,Roll_KP,Roll_KI,Roll_KD,KDDgain);
+PID_Alt PID_IR(MeanNum,IR_KP,IR_KI,IR_KD,IR_KDD,p20);
+
+//prototypes
+void PWM_change();
+void PWM_change2();
+void alt_update_Val();
+void sendstatus();
+float val,val2=0,val_test=0,x_plane,y_plane;
+char Calibrated;
+char flag=0;
+char selected_plane=3;
+float KD_NEW,KP_NEW;
+float AngleRoll,AnglePitch,AngleOffset[2],AngleYaw,yawOffset,y_old;
+Ticker timer,timer2;
+float acc_PitchPlane,acc_RollPlane,Pitchacc_Req,Rollacc_Req,Req_Pitch,Req_Roll;
+
+int main() {
+ KD_NEW=Pitch_KD;
+ KP_NEW=Pitch_KP;
+ //pc.baud(9600);
+ pc.baud(115200);
+ //PID_IR
+ PID_IR.Set_IN_Limits(ILowerIR,IUpperIR);
+ PID_IR.Set_OUT_Limits(OLowerPower,OUpperPower);
+
+ AngleOffset[0]=0;
+ AngleOffset[1]=0;
+ yawOffset=0;
+
+ //Yaw_Plan
+ Yaw_Plane.Set_IN_Limits(ILowerRPM,IUpperRPM);
+ Yaw_Plane.Set_OUT_Limits(OLowerPWM_yaw,OUpperPWM_yaw);
+ //Pitch_Plan
+ Pitch_Plan.Set_IN_Limits(ILowerRPM,IUpperRPM);
+ Pitch_Plan.Set_OUT_Limits(OLowerPWM,OUpperPWM);
+ //Roll_Plan
+ Roll_Plan.Set_IN_Limits(ILowerRPM,IUpperRPM);
+ Roll_Plan.Set_OUT_Limits(OLowerPWM,OUpperPWM);
+ //Angle.BeginInterrupt(0.039);
+ acc_PitchPlane=0;
+ acc_RollPlane=0;
+ Pitchacc_Req=0;
+ Rollacc_Req=0;
+ Req_Pitch=0;
+ Req_Roll=0;
+ val=0.00115;
+ Calibrated=0;
+ val2=0;
+ while(1){
+ while(!pc.readable());
+ pc.getc();
+ // timer.attach(alt_update_Val, 0.15);
+ timer2.attach(sendstatus,0.25);
+
+ t.reset();
+ t.start();
+ FILE *fp=fopen("/local/out.xls","a");
+
+ while(1) {
+ if(Angle.dmpReady)
+ {
+ PWM_change();
+ Angle.callMeanFilteredReadings();
+ //PWM_change2();
+ //val_test=PID_IR.findNominalVal(val2,cos(AnglePitch),cos(AngleRoll),Calibrated);
+
+ AngleYaw=Angle.Meanypr[0]-yawOffset;
+ AnglePitch=(Angle.Meanypr[1]-AngleOffset[0]);
+ AngleRoll=(Angle.Meanypr[2]-AngleOffset[1]);
+ if(abs(AngleYaw-y_old)<0.1*M_PI/180)yawOffset=yawOffset+(AngleYaw-y_old);
+ y_old=AngleYaw;
+ /*
+ acc_PitchPlane=sin(AngleRoll);
+ acc_RollPlane=sin(AnglePitch);
+ Req_Pitch=asin(Pitchacc_Req-acc_PitchPlane);
+ Req_Roll=asin(Rollacc_Req-acc_RollPlane);
+ if(Req_Pitch>5)Req_Pitch=10;
+ if(Req_Pitch<-5)Req_Pitch=-10;
+ if(Req_Roll>5)Req_Roll=10;
+ if(Req_Roll<-5)Req_Roll=-10;*/
+
+ Yaw_Plane.PWM_cal(0,AngleYaw,val,&x_plane,&y_plane);
+
+ if(selected_plane==1||selected_plane==3){
+ Pitch_Plan.PWM_cal(0*3.14/180/*0*/,-1*AnglePitch,x_plane/*val*/);
+ }
+ if(selected_plane==2||selected_plane==3){
+ Roll_Plan.PWM_cal(0,1*AngleRoll,y_plane/*val*/);
+ }
+ //fprintf(fp,"%f \t %f \t %f \t\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,AngleYaw*180/3.14);
+
+ //pc.printf("A1:%f A2:%f OP:%f OP2:%f\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,val,val_test);
+ //pc.printf("A1:%f A2:%f OP:%f RAlt:%f OP_test:%f alt:%f t:%f\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,val,val2,val_test,PID_IR.MeanIR(3),t.read());
+ // fprintf(fp,"%f \t %f \t %f \t %f \t %f \t",AngleRoll,Req_Roll,AnglePitch,Req_Pitch,t.read());
+
+/* fprintf(fp,"%f \t %f \t %f \t %f \t %f \t %f \t %f \t %f \t %f \t %f \t %f \t %f\r\n",(AnglePitch)*180/3.14,Pitch_Plan.readErrorVal(),Pitch_Plan.readErrorDVal(),Pitch_Plan.readGradientFunction(),Pitch_Plan.readSigmoindFunVal()
+ ,(AngleRoll)*180/3.14,Roll_Plan.readErrorVal(),Roll_Plan.readErrorDVal(),Roll_Plan.readGradientFunction(),Roll_Plan.readSigmoindFunVal()
+ ,val,t.read());
+*/ }
+ if(flag){
+ flag=0;
+ Pitch_Plan.PWM_cal(0,0,0.001);
+ Roll_Plan.PWM_cal(0,0,0.001);
+ Pitch_Plan.PWM_cal(0,0,0.001);
+ Roll_Plan.PWM_cal(0,0,0.001);
+ //timer.detach();
+ val2=0;
+ break;}
+ }
+ fclose(fp);
+
+ }
+}
+void PWM_change()
+{
+ if(pc.readable()) {
+ switch (pc.getc()) {
+ case 'u':
+ val += 0.00005;
+ val2 += 10;
+ break;
+ case 'd':
+ val -= 0.00005;
+ val2 -= 5;
+ break;
+ case 'w':
+ val += 0.00001;
+ break;
+ case 'x':
+ val -= 0.00001;
+ break;
+ case 'e':
+ val+= 0.000005;
+ break;
+ case 'f':
+ val-=0.000005;
+ break;
+ case '*':
+ val = 0.002;
+ break;
+ case 'm':
+ val =0.001;
+ break;
+ case 's':
+ val = 0.001;
+ flag=1;
+ break;
+ case'1':
+ KD_NEW+=0.1;
+ // Pitch_Plan.ChangeKDval(KD_NEW);
+ // Roll_Plan.ChangeKDval(KD_NEW);
+ break;
+ case'2':
+ KD_NEW-=0.1;
+ // Pitch_Plan.ChangeKDval(KD_NEW);
+ // Roll_Plan.ChangeKDval(KD_NEW);
+ break;
+ case'4':
+ KP_NEW+=0.001;
+ // Pitch_Plan.ChangeKDval(KD_NEW);
+ // Roll_Plan.ChangeKDval(KD_NEW);
+ break;
+ case'5':
+ KP_NEW-=0.001;
+ // Pitch_Plan.ChangeKPval(KD_NEW);
+ // Roll_Plan.ChangeKPval(KD_NEW);
+ break;
+ case 'c':
+ AngleOffset[0]=Angle.Meanypr[1];
+ AngleOffset[1]=Angle.Meanypr[2];
+ yawOffset=Angle.Meanypr[0];
+
+ Calibrated=1;
+
+ break;
+ /*case '1':
+ case '2':
+ case '4':
+ case '5':
+ */case '7':
+ selected_plane=1;
+ val = 0.001;
+ break;
+ case '8':
+ selected_plane=2;
+ val = 0.001;
+ break;
+ case '9':
+ selected_plane=3;
+ val = 0.001;
+ break;
+
+ case 'l':
+ PID_IR.Set_IN_Limits(newILowerIR,newIUpperIR);
+ PID_IR.Set_OUT_Limits(newOLowerPower,newOUpperPower);
+ break;
+ case 'p':
+ PID_IR.Set_IN_Limits(ILowerIR,IUpperIR);
+ PID_IR.Set_OUT_Limits(OLowerPower,OUpperPower);
+ break;
+
+ }
+ // pc.printf("char:%c",pc.getc());
+
+ }
+
+}
+
+
+void PWM_change2(){//distance in cm
+ if(pc.readable()) {
+ switch (pc.getc()) {
+ case 'u':
+ val2 += 5;
+ break;
+ case 'd':
+ val2-=5;
+ break;
+ case 's':
+ val2=0;
+ flag=1;
+ break;
+ case 'c':
+ AngleOffset[0]=Angle.Meanypr[1];
+ AngleOffset[1]=Angle.Meanypr[2];
+ yawOffset=Angle.Meanypr[0];
+ Calibrated=1;
+ break;
+ case 'm':
+ PID_IR.Set_IN_Limits(newILowerIR,newIUpperIR);
+ PID_IR.Set_OUT_Limits(newOLowerPower,newOUpperPower);
+ break;
+ case 'p':
+ PID_IR.Set_IN_Limits(ILowerIR,IUpperIR);
+ PID_IR.Set_OUT_Limits(OLowerPower,OUpperPower);
+ break;
+
+ }
+ }
+ }
+void alt_update_Val(){
+ val_test=PID_IR.findNominalVal(val2,cos(AnglePitch),cos(AngleRoll),Calibrated);
+ //val=PID_IR.findNominalVal(val2,cos(AnglePitch),cos(AngleRoll),Calibrated);
+
+ //pc.printf("here\r\n");
+
+ }
+void sendstatus(){
+ //pc.printf("A1:%f A2:%f OP:%f OP2:%f\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,val,val_test);
+ //pc.printf("A1:%f A2:%f OP:%f RAlt:%f OP_test:%f alt:%f t:%f\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,val,val2,val_test,PID_IR.MeanIR(3),t.read());
+ pc.printf("A1:%f A2:%f A3:%f OP:%f RA:%f\r\n",AnglePitch*180/3.14,AngleRoll*180/3.14,AngleYaw*180/3.14,val,val2);
+ }
\ No newline at end of file
diff -r 000000000000 -r e63996fd7d3e mbed.bld --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Fri Jul 03 11:16:02 2015 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/7cff1c4259d7 \ No newline at end of file