diff --git a/.gitignore b/.gitignore index 66a40e48..8c1a6502 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,9 @@ PIC18/MPU6050/Examples/MPU6050_raw.X/dist/ PIC18/MPU6050/Examples/MPU6050_raw.X/nbproject/private/ PIC18/MPU6050/Examples/MPU6050_raw.X/build/ *~ +/dsPIC30F/I2Cdev/I2CdevdsPic30F.X/nbproject/private/ +/dsPIC30F/I2Cdev/I2CdevdsPic30F.X/dist/default/ +/dsPIC30F/I2Cdev/testMCC.X/nbproject/private/ +/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/private/ +/dsPIC30F/MPU6050/Examples/MPU6050_example.X/build/default/ +/dsPIC30F/MPU6050/Examples/MPU6050_example.X/dist/default/ \ No newline at end of file diff --git a/dsPIC30F/I2Cdev/I2Cdev.c b/dsPIC30F/I2Cdev/I2Cdev.c new file mode 100644 index 00000000..cc968752 --- /dev/null +++ b/dsPIC30F/I2Cdev/I2Cdev.c @@ -0,0 +1,420 @@ +// I2Cdev library collection - Main I2C device class +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// 11/28/2014 by Marton Sebok +// +// Changelog: +// 2014-11-28 - ported to PIC18 peripheral library from Arduino code + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg +Copyright (c) 2014 Marton Sebok +Copyright (c) 2017 Daichou + * +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 "I2Cdev.h" + +/*uint16_t config2; +uint16_t config1 = (I2C_ON & I2C_IDLE_CON & I2C_CLK_HLD & + I2C_IPMI_DIS & I2C_7BIT_ADD & + I2C_SLW_DIS & I2C_SM_DIS & + I2C_GCALL_DIS & I2C_STR_DIS & + I2C_NACK & I2C_ACK_DIS & I2C_RCV_DIS & + I2C_STOP_DIS & I2C_RESTART_DIS & + I2C_START_DIS); +*/ +/** 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 + * @return Number of bytes read (-1 indicates failure) + */ +int8_t I2Cdev_readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data) { + IFS0bits.MI2CIF = 0; + IEC0bits.MI2CIE = 0; + /*master Start*/ + StartI2C(); + /* Clear interrupt flag */ + + /* Wait till Start sequence is completed */ + while(I2CCONbits.SEN); + + /*master send AD+W*/ + /* Write Slave Address (Write)*/ + MasterWriteI2C(devAddr << 1 | 0x00); + + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send Ack*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + //while(I2CSTATbits.ACKSTAT); + /*Master send RA*/ + /* Write Register Address */ + MasterWriteI2C(regAddr); + + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master Pause*/ + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + + /*Master Start*/ + StartI2C(); + /* Wait till Start sequence is completed */ + while(I2CCONbits.SEN); + + + + /*Master send AD+R*/ + /* Write Slave Address (Read)*/ + MasterWriteI2C(devAddr << 1 | 0x01); + + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send Ack*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + data[0] = MasterReadI2C(); + unsigned int i; + for (i = 1 ; i < length ; i++ ){ + AckI2C(); + while(I2CCONbits.ACKEN == 1); + data[i] = MasterReadI2C(); + } + NotAckI2C(); + while(I2CCONbits.ACKEN == 1); + /*Master Pause*/ + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + return length; +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data) { + return I2Cdev_readBytes(devAddr, regAddr, 1, data); +} + +/** Read multiple words from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of words to read + * @param data Buffer to store read data in + * @return Number of words read (-1 indicates failure) + */ +int8_t I2Cdev_readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data) { + unsigned char Onebyte[100]; + I2Cdev_readBytes(devAddr,regAddr,length*2,Onebyte); + unsigned int i; + for (int i = 0 ; i < length ; i++ ){ + data[i] = Onebyte[i*2] << 8 | Onebyte[i*2+1]; + } + return length; +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data) { + return I2Cdev_readWords(devAddr, regAddr, 1, data); +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data) { + uint8_t b; + uint8_t count = I2Cdev_readByte(devAddr, regAddr, &b); + *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 + * @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 b; + uint8_t count = I2Cdev_readWord(devAddr, regAddr, &b); + *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) + * @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) { + // 01101001 read byte + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 010 masked + // -> 010 shifted + uint8_t count, b; + if ((count = I2Cdev_readByte(devAddr, regAddr, &b)) != 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) + * @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) { + // 1101011001101001 read byte + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 010 masked + // -> 010 shifted + uint8_t count; + uint16_t w; + if ((count = I2Cdev_readWord(devAddr, regAddr, &w)) != 0) { + uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1); + w &= mask; + w >>= (bitStart - length + 1); + *data = w; + } + return count; +} + +/** Write multiple bytes to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of bytes to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev_writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data) { + IFS0bits.MI2CIF = 0; + IEC0bits.MI2CIE = 0; + /*Master Start*/ + StartI2C(); + /* Wait util Start sequence is completed */ + while(I2CCONbits.SEN); + /* Clear interrupt flag */ + IFS0bits.MI2CIF = 0; + + /*Master send AD+W*/ + /* Write Slave address (Write)*/ + MasterWriteI2C(devAddr << 1 | 0x00); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master send RA*/ + /* Write Slave address (Write)*/ + MasterWriteI2C(regAddr); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master send data*/ + /* Transmit string of data */ + uint8_t i; + for (i = 0 ; i < length ; i++){ + MasterWriteI2C(data[i]); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + } + + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + return true; +} + +/** 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 I2Cdev_writeBytes(devAddr, regAddr, 1, &data); +} + +/** Write multiple words to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of words to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev_writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data) { + unsigned char OneByte[100]; + unsigned int i; + for (i = 0 ; i < length ; i++){ + OneByte[i*2] = data[i]>>8; + OneByte[i*2+1] = data[i] & 0XFF; + } + I2Cdev_writeBytes(devAddr,regAddr,length*2,OneByte); + return true; +} + +/** 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 I2Cdev_writeWords(devAddr, regAddr, 1, &data); +} + +/** 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; + I2Cdev_readByte(devAddr, regAddr, &b); + b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); + return I2Cdev_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; + I2Cdev_readWord(devAddr, regAddr, &w); + w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum)); + return I2Cdev_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 (I2Cdev_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 I2Cdev_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 word + // 1010111110010110 original value (sample) + // 1010001110010110 original & ~mask + // 1010101110010110 masked | value + uint16_t w; + if (I2Cdev_readWord(devAddr, regAddr, &w) != 0) { + uint16_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 I2Cdev_writeWord(devAddr, regAddr, w); + } else { + return false; + } +} diff --git a/dsPIC30F/I2Cdev/I2Cdev.h b/dsPIC30F/I2Cdev/I2Cdev.h new file mode 100644 index 00000000..3f8eae11 --- /dev/null +++ b/dsPIC30F/I2Cdev/I2Cdev.h @@ -0,0 +1,68 @@ +// I2Cdev library collection - Main I2C device class header file +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// 11/28/2014 by Marton Sebok +// +// Changelog: +// 2014-11-28 - ported to PIC18 peripheral library from Arduino code + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg +Copyright (c) 2014 Marton Sebok +Copyright (c) 2017 Daichou + +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 _I2CDEV_H_ +#define _I2CDEV_H_ + +#ifndef __XC16 + #error Use XC16 for compiling +#endif + +#include +#include +#include +#include + +#define I2C_DATA_WAIT 152 //(20*I2C_DATA_WAIT*20 - 1) cycle + + +int8_t I2Cdev_readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data); +int8_t I2Cdev_readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data); +int8_t I2Cdev_readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data); +int8_t I2Cdev_readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data); +int8_t I2Cdev_readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data); +int8_t I2Cdev_readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data); +int8_t I2Cdev_readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); +int8_t I2Cdev_readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + +bool I2Cdev_writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data); +bool I2Cdev_writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); +bool I2Cdev_writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); +bool I2Cdev_writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); +bool I2Cdev_writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); +bool I2Cdev_writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); +bool I2Cdev_writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); +bool I2Cdev_writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + +#endif /* _I2CDEV_H_ */ diff --git a/dsPIC30F/I2Cdev/I2CdevdsPic30F.X/nbproject/project.xml b/dsPIC30F/I2Cdev/I2CdevdsPic30F.X/nbproject/project.xml new file mode 100644 index 00000000..d3be9e5f --- /dev/null +++ b/dsPIC30F/I2Cdev/I2CdevdsPic30F.X/nbproject/project.xml @@ -0,0 +1,17 @@ + + + com.microchip.mplab.nbide.embedded.makeproject + + + I2CdevdsPic30F + 231209f4-6ed3-4604-8ec8-3340e931ead8 + 0 + c + + h + + ISO-8859-1 + + + + diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.c b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.c new file mode 100644 index 00000000..29bd9eb3 --- /dev/null +++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.c @@ -0,0 +1,436 @@ +// I2Cdev library collection - Main I2C device class +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// 11/28/2014 by Marton Sebok +// +// Changelog: +// 2014-11-28 - ported to PIC18 peripheral library from Arduino code + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg +Copyright (c) 2014 Marton Sebok +Copyright (c) 2017 Daichou + * +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 "I2Cdev.h" + + +/*uint16_t config2; +uint16_t config1 = (I2C_ON & I2C_IDLE_CON & I2C_CLK_HLD & + I2C_IPMI_DIS & I2C_7BIT_ADD & + I2C_SLW_DIS & I2C_SM_DIS & + I2C_GCALL_DIS & I2C_STR_DIS & + I2C_NACK & I2C_ACK_DIS & I2C_RCV_DIS & + I2C_STOP_DIS & I2C_RESTART_DIS & + I2C_START_DIS); +*/ +/** 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 + * @return Number of bytes read (-1 indicates failure) + */ +int8_t I2Cdev_readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data) { + //int8_t count = 0; + IFS0bits.MI2CIF = 0; + IEC0bits.MI2CIE = 0; + //IdleI2C(); + /*master Start*/ + StartI2C(); + /* Clear interrupt flag */ + + /* Wait till Start sequence is completed */ + while(I2CCONbits.SEN); + + /*master send AD+W*/ + /* Write Slave Address (Write)*/ + MasterWriteI2C(devAddr << 1 | 0x00); + + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send Ack*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + //while(I2CSTATbits.ACKSTAT); + /*Master send RA*/ + /* Write Register Address */ + MasterWriteI2C(regAddr); + + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master Pause*/ + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + + /*Master Start*/ + StartI2C(); + /* Wait till Start sequence is completed */ + while(I2CCONbits.SEN); + + /*Master send AD+R*/ + /* Write Slave Address (Read)*/ + MasterWriteI2C(devAddr << 1 | 0x01); + /* Wait until address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send Ack*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Slave send DATA*/ + //uint16_t flag = MastergetsI2C(length,data,I2C_DATA_WAIT); + + /*Slave send NACK*/ + //MastergetsI2C(length,data,100); + //NotAckI2C(); + + data[0] = MasterReadI2C(); + unsigned int i; + for (i = 1 ; i < length ; i++ ){ + AckI2C(); + while(I2CCONbits.ACKEN == 1); + data[i] = MasterReadI2C(); + } + NotAckI2C(); + while(I2CCONbits.ACKEN == 1); + /*Master Pause*/ + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + //CloseI2C(); + //IdleI2C(); + return length; +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data) { + return I2Cdev_readBytes(devAddr, regAddr, 1, data); +} + +/** Read multiple words from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of words to read + * @param data Buffer to store read data in + * @return Number of words read (-1 indicates failure) + */ +int8_t I2Cdev_readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data) { + unsigned char Onebyte[100]; + I2Cdev_readBytes(devAddr,regAddr,length*2,Onebyte); + unsigned int i; + for (int i = 0 ; i < length ; i++ ){ + data[i] = Onebyte[i*2] << 8 | Onebyte[i*2+1]; + } + return length; +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data) { + return I2Cdev_readWords(devAddr, regAddr, 1, data); +} + +/** 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 + * @return Status of read operation (true = success) + */ +int8_t I2Cdev_readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data) { + uint8_t b; + uint8_t count = I2Cdev_readByte(devAddr, regAddr, &b); + *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 + * @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 b; + uint8_t count = I2Cdev_readWord(devAddr, regAddr, &b); + *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) + * @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) { + // 01101001 read byte + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 010 masked + // -> 010 shifted + uint8_t count, b; + if ((count = I2Cdev_readByte(devAddr, regAddr, &b)) != 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) + * @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) { + // 1101011001101001 read byte + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 010 masked + // -> 010 shifted + uint8_t count; + uint16_t w; + if ((count = I2Cdev_readWord(devAddr, regAddr, &w)) != 0) { + uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1); + w &= mask; + w >>= (bitStart - length + 1); + *data = w; + } + return count; +} + +/** Write multiple bytes to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of bytes to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev_writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data) { + //if (data[length-1] != '\0' && length != 1)return false; + //OpenI2C(config1,config2); + IFS0bits.MI2CIF = 0; + IEC0bits.MI2CIE = 0; + //IdleI2C(); + /*Master Start*/ + StartI2C(); + /* Wait util Start sequence is completed */ + while(I2CCONbits.SEN); + /* Clear interrupt flag */ + IFS0bits.MI2CIF = 0; + + /*Master send AD+W*/ + /* Write Slave address (Write)*/ + MasterWriteI2C(devAddr << 1 | 0x00); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master send RA*/ + /* Write Slave address (Write)*/ + MasterWriteI2C(regAddr); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + while(I2CSTATbits.ACKSTAT); + + /*Master send data*/ + /* Transmit string of data */ + //MasterputsI2C(data); + uint8_t i; + for (i = 0 ; i < length ; i++){ + MasterWriteI2C(data[i]); + /* Wait till address is transmitted */ + while(I2CSTATbits.TBF); // 8 clock cycles + + /*Slave send ACK*/ + while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + IFS0bits.MI2CIF = 0; // Clear interrupt flag + } + //while(!IFS0bits.MI2CIF); // Wait for 9th clock cycle + //IFS0bits.MI2CIF = 0; // Clear interrupt flag + StopI2C(); + /* Wait till stop sequence is completed */ + while(I2CCONbits.PEN); + //CloseI2C(); + //IdleI2C(); + return true; +} + +/** 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 I2Cdev_writeBytes(devAddr, regAddr, 1, &data); +} + +/** Write multiple words to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of words to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev_writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data) { + unsigned char OneByte[100]; + unsigned int i; + for (i = 0 ; i < length ; i++){ + OneByte[i*2] = data[i]>>8; + OneByte[i*2+1] = data[i] & 0XFF; + } + I2Cdev_writeBytes(devAddr,regAddr,length*2,OneByte); + return true; +} + +/** 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 I2Cdev_writeWords(devAddr, regAddr, 1, &data); +} + +/** 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; + I2Cdev_readByte(devAddr, regAddr, &b); + b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); + return I2Cdev_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; + I2Cdev_readWord(devAddr, regAddr, &w); + w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum)); + return I2Cdev_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 (I2Cdev_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 I2Cdev_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 word + // 1010111110010110 original value (sample) + // 1010001110010110 original & ~mask + // 1010101110010110 masked | value + uint16_t w; + if (I2Cdev_readWord(devAddr, regAddr, &w) != 0) { + uint16_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 I2Cdev_writeWord(devAddr, regAddr, w); + } else { + return false; + } +} diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.h b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.h new file mode 100644 index 00000000..3f8eae11 --- /dev/null +++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/I2Cdev.h @@ -0,0 +1,68 @@ +// I2Cdev library collection - Main I2C device class header file +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// 11/28/2014 by Marton Sebok +// +// Changelog: +// 2014-11-28 - ported to PIC18 peripheral library from Arduino code + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg +Copyright (c) 2014 Marton Sebok +Copyright (c) 2017 Daichou + +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 _I2CDEV_H_ +#define _I2CDEV_H_ + +#ifndef __XC16 + #error Use XC16 for compiling +#endif + +#include +#include +#include +#include + +#define I2C_DATA_WAIT 152 //(20*I2C_DATA_WAIT*20 - 1) cycle + + +int8_t I2Cdev_readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data); +int8_t I2Cdev_readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data); +int8_t I2Cdev_readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data); +int8_t I2Cdev_readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data); +int8_t I2Cdev_readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data); +int8_t I2Cdev_readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data); +int8_t I2Cdev_readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); +int8_t I2Cdev_readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + +bool I2Cdev_writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data); +bool I2Cdev_writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); +bool I2Cdev_writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); +bool I2Cdev_writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); +bool I2Cdev_writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); +bool I2Cdev_writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); +bool I2Cdev_writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); +bool I2Cdev_writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + +#endif /* _I2CDEV_H_ */ diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.c b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.c new file mode 100644 index 00000000..a976419e --- /dev/null +++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.c @@ -0,0 +1,3588 @@ +// 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 +// 11/28/2014 by Marton Sebok +// +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release +// 2014-11-28 - ported to PIC18 peripheral library from Arduino code + +// 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 +Copyright (c) 2014 Marton Sebok + +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" + +MPU6050_t mpu6050; + +/** Specific address constructor. + * @param address I2C address + * @see MPU6050_DEFAULT_ADDRESS + * @see MPU6050_ADDRESS_AD0_LOW + * @see MPU6050_ADDRESS_AD0_HIGH + */ +void MPU6050(uint8_t address) +{ + mpu6050.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() +{ + MPU6050_setClockSource(MPU6050_CLOCK_PLL_XGYRO); + MPU6050_setFullScaleGyroRange(MPU6050_GYRO_FS_250); + MPU6050_setFullScaleAccelRange(MPU6050_ACCEL_FS_2); + MPU6050_setSleepEnabled(false); +} + +/** 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() +{ + return MPU6050_getDeviceID() == 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(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_SMPLRT_DIV, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ * 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]
+ * 
+ * + * @return FSYNC configuration value + */ +uint8_t MPU6050_getExternalFrameSync() +{ + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_CONFIG, + MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ *          |   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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, + MPU6050_CFG_DLPF_CFG_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_GYRO_CONFIG, + MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, + MPU6050_ACONFIG_XA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, + MPU6050_ACONFIG_YA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, + MPU6050_ACONFIG_ZA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, + MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ *    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.
+ * 
+ * + *
+ * 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
+ * 
+ * + * @return Current high-pass filter configuration + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +uint8_t MPU6050_getDHPFMode() +{ + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, + MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_FF_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_FF_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ZRMOT_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ZRMOT_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current temperature FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getTempFIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getXGyroFIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getYGyroFIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getZGyroFIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getAccelFIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave2FIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave1FIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave0FIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, + MPU6050_MULT_MST_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, + MPU6050_WAIT_FOR_ES_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU6050_RA_MST_CTRL + */ +bool MPU6050_getSlave3FIFOEnabled() +{ + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, + MPU6050_SLV_3_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, + MPU6050_I2C_MST_P_NSR_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @return Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +uint8_t MPU6050_getMasterClockSpeed() +{ + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, + MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_ADDR + num * 3, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_REG + num * 3, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, + MPU6050_I2C_SLV_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, + MPU6050_I2C_SLV_BYTE_SW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, + MPU6050_I2C_SLV_REG_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, + MPU6050_I2C_SLV_GRP_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num * 3, + MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_ADDR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_REG, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, + MPU6050_I2C_SLV4_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, + MPU6050_I2C_SLV4_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, + MPU6050_I2C_SLV4_REG_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, + MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_DI, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_PASS_THROUGH_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV4_DONE_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_LOST_ARB_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV4_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV3_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV2_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV1_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, + MPU6050_MST_I2C_SLV0_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_INT_LEVEL_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_INT_OPEN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_LATCH_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_INT_RD_CLEAR_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_FSYNC_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_I2C_BYPASS_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, + MPU6050_INTCFG_CLKOUT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, + MPU6050_INTERRUPT_MOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, + MPU6050_INTERRUPT_ZMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, + MPU6050_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, + MPU6050_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, + MPU6050_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, + MPU6050_INTERRUPT_MOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, + MPU6050_INTERRUPT_ZMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, + MPU6050_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, + MPU6050_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, + MPU6050_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer); + return mpu6050.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) +{ + MPU6050_getMotion6(ax, ay, az, gx, gy, gz); + // TODO: magnetometer integration +} +/** 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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, mpu6050.buffer); + *ax = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *ay = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *az = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.buffer[5]; + *gx = (((int16_t)mpu6050.buffer[8]) << 8) | mpu6050.buffer[9]; + *gy = (((int16_t)mpu6050.buffer[10]) << 8) | mpu6050.buffer[11]; + *gz = (((int16_t)mpu6050.buffer[12]) << 8) | mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, mpu6050.buffer); + *x = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *y = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *z = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_TEMP_OUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_GYRO_XOUT_H, 6, mpu6050.buffer); + *x = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *y = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *z = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_XOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_YOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, + mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, + mpu6050.buffer); + return (((uint16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, + mpu6050.buffer); + return (((uint32_t)mpu6050.buffer[0]) << 24) | (((uint32_t)mpu6050.buffer[1]) << + 16) | (((uint16_t)mpu6050.buffer[2]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_XNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_XPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_YNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_YPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_ZNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_ZPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, + MPU6050_MOTION_MOT_ZRMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, + MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, + MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, + mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * 
+ * + * 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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, + MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * 
+ * + * 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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, + MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer is disabled. The FIFO mpu6050.buffer + * cannot be written to or read from while disabled. The FIFO mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, + MPU6050_USERCTRL_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, + MPU6050_USERCTRL_I2C_MST_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, + MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, + mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, + MPU6050_PWR1_TEMP_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, + MPU6050_PWR1_CLKSEL_LENGTH, mpu6050.buffer); + return mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.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: + * + *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * 
+ *
+ * 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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2,
+	                MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH,
+	                mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT,
+	               mpu6050.buffer);
+	return mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2,
+	                MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO mpu6050.buffer size.
+ * This value indicates the number of bytes stored in the FIFO mpu6050.buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO mpu6050.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 mpu6050.buffer size
+ */
+uint16_t MPU6050_getFIFOCount()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_FIFO_COUNTH, 2, mpu6050.buffer);
+	return (((uint16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO mpu6050.buffer.
+ * This register is used to read and write data from the FIFO mpu6050.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 mpu6050.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 mpu6050.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 mpu6050.buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO mpu6050.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 mpu6050.buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO mpu6050.buffer
+ */
+uint8_t MPU6050_getFIFOByte()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_FIFO_R_W, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_getFIFOBytes(uint8_t *data, uint8_t length)
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO mpu6050.buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6050_setFIFOByte(uint8_t data)
+{
+	I2Cdev_writeByte(mpu6050.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(mpu6050.devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT,
+	                MPU6050_WHO_AM_I_LENGTH, mpu6050.buffer);
+	return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC,
+	               MPU6050_TC_OTP_BNK_VLD_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setOTPBankValid(bool enabled)
+{
+	I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC,
+	                MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU6050_getXGyroOffsetTC()
+{
+	I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+	                MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setXGyroOffsetTC(int8_t offset)
+{
+	I2Cdev_writeBits(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+	                 MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6050_getYGyroOffsetTC()
+{
+	I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+	                MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setYGyroOffsetTC(int8_t offset)
+{
+	I2Cdev_writeBits(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+	                 MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6050_getZGyroOffsetTC()
+{
+	I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT,
+	                MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setZGyroOffsetTC(int8_t offset)
+{
+	I2Cdev_writeBits(mpu6050.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(mpu6050.devAddr, MPU6050_RA_X_FINE_GAIN, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setXFineGain(int8_t gain)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6050_getYFineGain()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_Y_FINE_GAIN, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setYFineGain(int8_t gain)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6050_getZFineGain()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_Z_FINE_GAIN, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setZFineGain(int8_t gain)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6050_getXAccelOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_XA_OFFS_H, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setXAccelOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6050_getYAccelOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_YA_OFFS_H, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setYAccelOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6050_getZAccelOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_ZA_OFFS_H, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setZAccelOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6050_getXGyroOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_XG_OFFS_USRH, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setXGyroOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6050_getYGyroOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_YG_OFFS_USRH, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setYGyroOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6050_getZGyroOffset()
+{
+	I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, mpu6050.buffer);
+	return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setZGyroOffset(int16_t offset)
+{
+	I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6050_getIntPLLReadyEnabled()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE,
+	               MPU6050_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setIntPLLReadyEnabled(bool enabled)
+{
+	I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE,
+	                MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU6050_getIntDMPEnabled()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE,
+	               MPU6050_INTERRUPT_DMP_INT_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setIntDMPEnabled(bool enabled)
+{
+	I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE,
+	                MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6050_getDMPInt5Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt4Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt3Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt2Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt1Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt0Status()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT,
+	               mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6050_getIntPLLReadyStatus()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_STATUS,
+	               MPU6050_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+bool MPU6050_getIntDMPStatus()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_STATUS,
+	               MPU6050_INTERRUPT_DMP_INT_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6050_getDMPEnabled()
+{
+	I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_USER_CTRL,
+	               MPU6050_USERCTRL_DMP_EN_BIT, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setDMPEnabled(bool enabled)
+{
+	I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_USER_CTRL,
+	                MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU6050_resetDMP()
+{
+	I2Cdev_writeBit(mpu6050.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(mpu6050.devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU6050_setMemoryStartAddress(uint8_t address)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6050_readMemoryByte()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_MEM_R_W, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_writeMemoryByte(uint8_t data)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void MPU6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank,
+                             uint8_t address)
+{
+	MPU6050_setMemoryBank(bank, false, false);
+	MPU6050_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(mpu6050.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++;
+			MPU6050_setMemoryBank(bank, false, false);
+			MPU6050_setMemoryStartAddress(address);
+		}
+	}
+}
+/*bool MPU6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+    MPU6050_setMemoryBank(bank, false, false);
+    MPU6050_setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer;
+    uint8_t *progBuffer;
+    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(mpu6050.devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            MPU6050_setMemoryBank(bank, false, false);
+            MPU6050_setMemoryStartAddress(address);
+            I2Cdev_readBytes(mpu6050.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++;
+            MPU6050_setMemoryBank(bank, false, false);
+            MPU6050_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 MPU6050_writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
+    uint8_t *progBuffer, success, special;
+    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 = MPU6050_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(mpu6050.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 MPU6050_writeDMPConfigurationSet(data, dataSize, true);
+}*/
+
+// DMP_CFG_1 register
+
+uint8_t MPU6050_getDMPConfig1()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_1, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setDMPConfig1(uint8_t config)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6050_getDMPConfig2()
+{
+	I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_2, mpu6050.buffer);
+	return mpu6050.buffer[0];
+}
+void MPU6050_setDMPConfig2(uint8_t config)
+{
+	I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.h b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.h
new file mode 100644
index 00000000..830760fc
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050.h
@@ -0,0 +1,786 @@
+// 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 
+// 11/28/2014 by Marton Sebok 
+//
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ...        - ongoing debug release
+//     2014-11-28 - ported to PIC18 peripheral library from Arduino code
+
+// 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
+Copyright (c) 2014 Marton Sebok
+
+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"
+
+#if ((defined MPU6050_INCLUDE_DMP_MOTIONAPPS20) || (defined MPU6050_INCLUDE_DMP_MOTIONAPPS41))
+    #error DMP is not supported yet
+#endif
+
+#define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS     MPU6050_ADDRESS_AD0_LOW
+
+#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 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
+
+typedef struct MPU6050_t {
+    uint8_t devAddr;
+    uint8_t buffer[14];
+} MPU6050_t;
+
+void MPU6050(uint8_t address);
+
+void MPU6050_initialize();
+bool MPU6050_testConnection();
+
+// AUX_VDDIO register
+uint8_t MPU6050_getAuxVDDIOLevel();
+void MPU6050_setAuxVDDIOLevel(uint8_t level);
+
+// SMPLRT_DIV register
+uint8_t MPU6050_getRate();
+void MPU6050_setRate(uint8_t rate);
+
+// CONFIG register
+uint8_t MPU6050_getExternalFrameSync();
+void MPU6050_setExternalFrameSync(uint8_t sync);
+uint8_t MPU6050_getDLPFMode();
+void MPU6050_setDLPFMode(uint8_t bandwidth);
+
+// GYRO_CONFIG register
+uint8_t MPU6050_getFullScaleGyroRange();
+void MPU6050_setFullScaleGyroRange(uint8_t range);
+
+// ACCEL_CONFIG register
+bool MPU6050_getAccelXSelfTest();
+void MPU6050_setAccelXSelfTest(bool enabled);
+bool MPU6050_getAccelYSelfTest();
+void MPU6050_setAccelYSelfTest(bool enabled);
+bool MPU6050_getAccelZSelfTest();
+void MPU6050_setAccelZSelfTest(bool enabled);
+uint8_t MPU6050_getFullScaleAccelRange();
+void MPU6050_setFullScaleAccelRange(uint8_t range);
+uint8_t MPU6050_getDHPFMode();
+void MPU6050_setDHPFMode(uint8_t mode);
+
+// FF_THR register
+uint8_t MPU6050_getFreefallDetectionThreshold();
+void MPU6050_setFreefallDetectionThreshold(uint8_t threshold);
+
+// FF_DUR register
+uint8_t MPU6050_getFreefallDetectionDuration();
+void MPU6050_setFreefallDetectionDuration(uint8_t duration);
+
+// MOT_THR register
+uint8_t MPU6050_getMotionDetectionThreshold();
+void MPU6050_setMotionDetectionThreshold(uint8_t threshold);
+
+// MOT_DUR register
+uint8_t MPU6050_getMotionDetectionDuration();
+void MPU6050_setMotionDetectionDuration(uint8_t duration);
+
+// ZRMOT_THR register
+uint8_t MPU6050_getZeroMotionDetectionThreshold();
+void MPU6050_setZeroMotionDetectionThreshold(uint8_t threshold);
+
+// ZRMOT_DUR register
+uint8_t MPU6050_getZeroMotionDetectionDuration();
+void MPU6050_setZeroMotionDetectionDuration(uint8_t duration);
+
+// FIFO_EN register
+bool MPU6050_getTempFIFOEnabled();
+void MPU6050_setTempFIFOEnabled(bool enabled);
+bool MPU6050_getXGyroFIFOEnabled();
+void MPU6050_setXGyroFIFOEnabled(bool enabled);
+bool MPU6050_getYGyroFIFOEnabled();
+void MPU6050_setYGyroFIFOEnabled(bool enabled);
+bool MPU6050_getZGyroFIFOEnabled();
+void MPU6050_setZGyroFIFOEnabled(bool enabled);
+bool MPU6050_getAccelFIFOEnabled();
+void MPU6050_setAccelFIFOEnabled(bool enabled);
+bool MPU6050_getSlave2FIFOEnabled();
+void MPU6050_setSlave2FIFOEnabled(bool enabled);
+bool MPU6050_getSlave1FIFOEnabled();
+void MPU6050_setSlave1FIFOEnabled(bool enabled);
+bool MPU6050_getSlave0FIFOEnabled();
+void MPU6050_setSlave0FIFOEnabled(bool enabled);
+
+// I2C_MST_CTRL register
+bool MPU6050_getMultiMasterEnabled();
+void MPU6050_setMultiMasterEnabled(bool enabled);
+bool MPU6050_getWaitForExternalSensorEnabled();
+void MPU6050_setWaitForExternalSensorEnabled(bool enabled);
+bool MPU6050_getSlave3FIFOEnabled();
+void MPU6050_setSlave3FIFOEnabled(bool enabled);
+bool MPU6050_getSlaveReadWriteTransitionEnabled();
+void MPU6050_setSlaveReadWriteTransitionEnabled(bool enabled);
+uint8_t MPU6050_getMasterClockSpeed();
+void MPU6050_setMasterClockSpeed(uint8_t speed);
+
+// I2C_SLV* registers (Slave 0-3)
+uint8_t MPU6050_getSlaveAddress(uint8_t num);
+void MPU6050_setSlaveAddress(uint8_t num, uint8_t address);
+uint8_t MPU6050_getSlaveRegister(uint8_t num);
+void MPU6050_setSlaveRegister(uint8_t num, uint8_t reg);
+bool MPU6050_getSlaveEnabled(uint8_t num);
+void MPU6050_setSlaveEnabled(uint8_t num, bool enabled);
+bool MPU6050_getSlaveWordByteSwap(uint8_t num);
+void MPU6050_setSlaveWordByteSwap(uint8_t num, bool enabled);
+bool MPU6050_getSlaveWriteMode(uint8_t num);
+void MPU6050_setSlaveWriteMode(uint8_t num, bool mode);
+bool MPU6050_getSlaveWordGroupOffset(uint8_t num);
+void MPU6050_setSlaveWordGroupOffset(uint8_t num, bool enabled);
+uint8_t MPU6050_getSlaveDataLength(uint8_t num);
+void MPU6050_setSlaveDataLength(uint8_t num, uint8_t length);
+
+// I2C_SLV* registers (Slave 4)
+uint8_t MPU6050_getSlave4Address();
+void MPU6050_setSlave4Address(uint8_t address);
+uint8_t MPU6050_getSlave4Register();
+void MPU6050_setSlave4Register(uint8_t reg);
+void MPU6050_setSlave4OutputByte(uint8_t data);
+bool MPU6050_getSlave4Enabled();
+void MPU6050_setSlave4Enabled(bool enabled);
+bool MPU6050_getSlave4InterruptEnabled();
+void MPU6050_setSlave4InterruptEnabled(bool enabled);
+bool MPU6050_getSlave4WriteMode();
+void MPU6050_setSlave4WriteMode(bool mode);
+uint8_t MPU6050_getSlave4MasterDelay();
+void MPU6050_setSlave4MasterDelay(uint8_t delay);
+uint8_t MPU6050_getSlate4InputByte();
+
+// I2C_MST_STATUS register
+bool MPU6050_getPassthroughStatus();
+bool MPU6050_getSlave4IsDone();
+bool MPU6050_getLostArbitration();
+bool MPU6050_getSlave4Nack();
+bool MPU6050_getSlave3Nack();
+bool MPU6050_getSlave2Nack();
+bool MPU6050_getSlave1Nack();
+bool MPU6050_getSlave0Nack();
+
+// INT_PIN_CFG register
+bool MPU6050_getInterruptMode();
+void MPU6050_setInterruptMode(bool mode);
+bool MPU6050_getInterruptDrive();
+void MPU6050_setInterruptDrive(bool drive);
+bool MPU6050_getInterruptLatch();
+void MPU6050_setInterruptLatch(bool latch);
+bool MPU6050_getInterruptLatchClear();
+void MPU6050_setInterruptLatchClear(bool clear);
+bool MPU6050_getFSyncInterruptLevel();
+void MPU6050_setFSyncInterruptLevel(bool level);
+bool MPU6050_getFSyncInterruptEnabled();
+void MPU6050_setFSyncInterruptEnabled(bool enabled);
+bool MPU6050_getI2CBypassEnabled();
+void MPU6050_setI2CBypassEnabled(bool enabled);
+bool MPU6050_getClockOutputEnabled();
+void MPU6050_setClockOutputEnabled(bool enabled);
+
+// INT_ENABLE register
+uint8_t MPU6050_getIntEnabled();
+void MPU6050_setIntEnabled(uint8_t enabled);
+bool MPU6050_getIntFreefallEnabled();
+void MPU6050_setIntFreefallEnabled(bool enabled);
+bool MPU6050_getIntMotionEnabled();
+void MPU6050_setIntMotionEnabled(bool enabled);
+bool MPU6050_getIntZeroMotionEnabled();
+void MPU6050_setIntZeroMotionEnabled(bool enabled);
+bool MPU6050_getIntFIFOBufferOverflowEnabled();
+void MPU6050_setIntFIFOBufferOverflowEnabled(bool enabled);
+bool MPU6050_getIntI2CMasterEnabled();
+void MPU6050_setIntI2CMasterEnabled(bool enabled);
+bool MPU6050_getIntDataReadyEnabled();
+void MPU6050_setIntDataReadyEnabled(bool enabled);
+
+// INT_STATUS register
+uint8_t MPU6050_getIntStatus();
+bool MPU6050_getIntFreefallStatus();
+bool MPU6050_getIntMotionStatus();
+bool MPU6050_getIntZeroMotionStatus();
+bool MPU6050_getIntFIFOBufferOverflowStatus();
+bool MPU6050_getIntI2CMasterStatus();
+bool MPU6050_getIntDataReadyStatus();
+
+// ACCEL_*OUT_* registers
+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);
+void MPU6050_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+void MPU6050_getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+int16_t MPU6050_getAccelerationX();
+int16_t MPU6050_getAccelerationY();
+int16_t MPU6050_getAccelerationZ();
+
+// TEMP_OUT_* registers
+int16_t MPU6050_getTemperature();
+
+// GYRO_*OUT_* registers
+void MPU6050_getRotation(int16_t* x, int16_t* y, int16_t* z);
+int16_t MPU6050_getRotationX();
+int16_t MPU6050_getRotationY();
+int16_t MPU6050_getRotationZ();
+
+// EXT_SENS_DATA_* registers
+uint8_t MPU6050_getExternalSensorByte(int position);
+uint16_t MPU6050_getExternalSensorWord(int position);
+uint32_t getExternalSensorDWord(int position);
+
+// MOT_DETECT_STATUS register
+bool MPU6050_getXNegMotionDetected();
+bool MPU6050_getXPosMotionDetected();
+bool MPU6050_getYNegMotionDetected();
+bool MPU6050_getYPosMotionDetected();
+bool MPU6050_getZNegMotionDetected();
+bool MPU6050_getZPosMotionDetected();
+bool MPU6050_getZeroMotionDetected();
+
+// I2C_SLV*_DO register
+void MPU6050_setSlaveOutputByte(uint8_t num, uint8_t data);
+
+// I2C_MST_DELAY_CTRL register
+bool MPU6050_getExternalShadowDelayEnabled();
+void MPU6050_setExternalShadowDelayEnabled(bool enabled);
+bool MPU6050_getSlaveDelayEnabled(uint8_t num);
+void MPU6050_setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+// SIGNAL_PATH_RESET register
+void MPU6050_resetGyroscopePath();
+void MPU6050_resetAccelerometerPath();
+void MPU6050_resetTemperaturePath();
+
+// MOT_DETECT_CTRL register
+uint8_t MPU6050_getAccelerometerPowerOnDelay();
+void MPU6050_setAccelerometerPowerOnDelay(uint8_t delay);
+uint8_t MPU6050_getFreefallDetectionCounterDecrement();
+void MPU6050_setFreefallDetectionCounterDecrement(uint8_t decrement);
+uint8_t MPU6050_getMotionDetectionCounterDecrement();
+void MPU6050_setMotionDetectionCounterDecrement(uint8_t decrement);
+
+// USER_CTRL register
+bool MPU6050_getFIFOEnabled();
+void MPU6050_setFIFOEnabled(bool enabled);
+bool MPU6050_getI2CMasterModeEnabled();
+void MPU6050_setI2CMasterModeEnabled(bool enabled);
+void MPU6050_switchSPIEnabled(bool enabled);
+void MPU6050_resetFIFO();
+void MPU6050_resetI2CMaster();
+void MPU6050_resetSensors();
+
+// PWR_MGMT_1 register
+void MPU6050_reset();
+bool MPU6050_getSleepEnabled();
+void MPU6050_setSleepEnabled(bool enabled);
+bool MPU6050_getWakeCycleEnabled();
+void MPU6050_setWakeCycleEnabled(bool enabled);
+bool MPU6050_getTempSensorEnabled();
+void MPU6050_setTempSensorEnabled(bool enabled);
+uint8_t MPU6050_getClockSource();
+void MPU6050_setClockSource(uint8_t source);
+
+// PWR_MGMT_2 register
+uint8_t MPU6050_getWakeFrequency();
+void MPU6050_setWakeFrequency(uint8_t frequency);
+bool MPU6050_getStandbyXAccelEnabled();
+void MPU6050_setStandbyXAccelEnabled(bool enabled);
+bool MPU6050_getStandbyYAccelEnabled();
+void MPU6050_setStandbyYAccelEnabled(bool enabled);
+bool MPU6050_getStandbyZAccelEnabled();
+void MPU6050_setStandbyZAccelEnabled(bool enabled);
+bool MPU6050_getStandbyXGyroEnabled();
+void MPU6050_setStandbyXGyroEnabled(bool enabled);
+bool MPU6050_getStandbyYGyroEnabled();
+void MPU6050_setStandbyYGyroEnabled(bool enabled);
+bool MPU6050_getStandbyZGyroEnabled();
+void MPU6050_setStandbyZGyroEnabled(bool enabled);
+
+// FIFO_COUNT_* registers
+uint16_t MPU6050_getFIFOCount();
+
+// FIFO_R_W register
+uint8_t MPU6050_getFIFOByte();
+void MPU6050_setFIFOByte(uint8_t data);
+void MPU6050_getFIFOBytes(uint8_t *data, uint8_t length);
+
+// WHO_AM_I register
+uint8_t MPU6050_getDeviceID();
+void MPU6050_setDeviceID(uint8_t id);
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+uint8_t MPU6050_getOTPBankValid();
+void MPU6050_setOTPBankValid(bool enabled);
+int8_t getXGyroOffsetTC();
+void MPU6050_setXGyroOffsetTC(int8_t offset);
+
+// YG_OFFS_TC register
+int8_t getYGyroOffsetTC();
+void MPU6050_setYGyroOffsetTC(int8_t offset);
+
+// ZG_OFFS_TC register
+int8_t getZGyroOffsetTC();
+void MPU6050_setZGyroOffsetTC(int8_t offset);
+
+// X_FINE_GAIN register
+int8_t getXFineGain();
+void MPU6050_setXFineGain(int8_t gain);
+
+// Y_FINE_GAIN register
+int8_t getYFineGain();
+void MPU6050_setYFineGain(int8_t gain);
+
+// Z_FINE_GAIN register
+int8_t getZFineGain();
+void MPU6050_setZFineGain(int8_t gain);
+
+// XA_OFFS_* registers
+int16_t MPU6050_getXAccelOffset();
+void MPU6050_setXAccelOffset(int16_t offset);
+
+// YA_OFFS_* register
+int16_t MPU6050_getYAccelOffset();
+void MPU6050_setYAccelOffset(int16_t offset);
+
+// ZA_OFFS_* register
+int16_t MPU6050_getZAccelOffset();
+void MPU6050_setZAccelOffset(int16_t offset);
+
+// XG_OFFS_USR* registers
+int16_t MPU6050_getXGyroOffset();
+void MPU6050_setXGyroOffset(int16_t offset);
+
+// YG_OFFS_USR* register
+int16_t MPU6050_getYGyroOffset();
+void MPU6050_setYGyroOffset(int16_t offset);
+
+// ZG_OFFS_USR* register
+int16_t MPU6050_getZGyroOffset();
+void MPU6050_setZGyroOffset(int16_t offset);
+
+// INT_ENABLE register (DMP functions)
+bool MPU6050_getIntPLLReadyEnabled();
+void MPU6050_setIntPLLReadyEnabled(bool enabled);
+bool MPU6050_getIntDMPEnabled();
+void MPU6050_setIntDMPEnabled(bool enabled);
+
+// DMP_INT_STATUS
+bool MPU6050_getDMPInt5Status();
+bool MPU6050_getDMPInt4Status();
+bool MPU6050_getDMPInt3Status();
+bool MPU6050_getDMPInt2Status();
+bool MPU6050_getDMPInt1Status();
+bool MPU6050_getDMPInt0Status();
+
+// INT_STATUS register (DMP functions)
+bool MPU6050_getIntPLLReadyStatus();
+bool MPU6050_getIntDMPStatus();
+
+// USER_CTRL register (DMP functions)
+bool MPU6050_getDMPEnabled();
+void MPU6050_setDMPEnabled(bool enabled);
+void MPU6050_resetDMP();
+
+// BANK_SEL register
+void MPU6050_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank);
+
+// MEM_START_ADDR register
+void MPU6050_setMemoryStartAddress(uint8_t address);
+
+// MEM_R_W register
+uint8_t MPU6050_readMemoryByte();
+void MPU6050_writeMemoryByte(uint8_t data);
+void MPU6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address);
+//bool MPU6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem);
+//bool MPU6050_writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+
+//bool MPU6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem);
+//bool MPU6050_writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+// DMP_CFG_1 register
+uint8_t MPU6050_getDMPConfig1();
+void MPU6050_setDMPConfig1(uint8_t config);
+
+// DMP_CFG_2 register
+uint8_t MPU6050_getDMPConfig2();
+void MPU6050_setDMPConfig2(uint8_t config);
+
+#endif /* _MPU6050_H_ */
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050_example_main.c b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050_example_main.c
new file mode 100644
index 00000000..10605f04
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/MPU6050_example_main.c
@@ -0,0 +1,250 @@
+/*
+ * File:   LEDMain.c
+ * Author: tommycc
+ *
+ * Created on March 1, 2017, 3:49 PM
+ */
+
+
+
+// DSPIC30F4013 Configuration Bit Settings
+
+// 'C' source line config statements
+
+// FOSC
+#pragma config FOSFPR = ECIO       // Oscillator (ECIO w/PLL 8x)
+#pragma config FCKSMEN = CSW_FSCM_OFF   // Clock Switching and Monitor (Sw Disabled, Mon Disabled)
+
+// FWDT
+#pragma config FWPSB = WDTPSB_16        // WDT Prescaler B (1:16)
+#pragma config FWPSA = WDTPSA_512       // WDT Prescaler A (1:512)
+#pragma config WDT = WDT_OFF            // Watchdog Timer (Disabled)
+
+// FBORPOR
+#pragma config FPWRT = PWRT_OFF         // POR Timer Value (Timer Disabled)
+#pragma config BODENV = BORV20          // Brown Out Voltage (Reserved)
+#pragma config BOREN = PBOR_OFF         // PBOR Enable (Disabled)
+#pragma config MCLRE = MCLR_EN          // Master Clear Enable (Enabled)
+
+// FGS
+#pragma config GWRP = GWRP_OFF          // General Code Segment Write Protect (Disabled)
+#pragma config GCP = CODE_PROT_OFF      // General Segment Code Protection (Disabled)
+
+// FICD
+#pragma config ICS = ICS_PGD            // Comm Channel Select (Use PGC/EMUC and PGD/EMUD)
+
+// #pragma config statements should precede project file includes.
+// Use project enums instead of #define for ON and OFF.
+
+#include 
+
+
+
+#include
+#include
+#include
+#include"MPU6050.h"
+#include"I2Cdev.h"
+/* Received data is stored in array Buf  */
+char Buf[80];
+char* Receivedddata = Buf;
+int16_t ax, ay, az, gx, gy, gz;
+/* This is UART1 transmit ISR */
+void __attribute__((__interrupt__)) _U2TXInterrupt(void)
+{  
+   IFS1bits.U2TXIF = 0;
+}
+
+/*******************************************************************************/
+//  delay us using for-loop
+/*******************************************************************************/
+void delay_us( unsigned int usec )
+{
+	unsigned int i;
+	//?   ?   ?   ?   ?   ?   ?   ?   ?   ?              //40 MIPS ,
+	for ( i = 0 ; i < usec * 2;
+	        i++ ) {                //for-loop 8Tcy -> 1us -> add two NOP()
+		asm("NOP");
+		asm("NOP");
+	}
+}
+
+/*******************************************************************************/
+// delay ms using Timer 1 interrupt
+/*******************************************************************************/
+void delay_ms( unsigned int msec )
+{
+	int i = 0;
+	for (i = 0; i < msec; i++)
+		delay_us(1000);
+}
+int main(void)
+{
+    TRISCbits.TRISC14 = 0;
+    LATCbits.LATC14 = 1;
+    while(1){
+        /* Data to be transmitted using UART communication module */
+        TRISFbits.TRISF3 = 0;
+        TRISFbits.TRISF2 = 0;
+        char Buffer[80];
+        /* Holds the value of baud register   */
+        unsigned int baudvalue;
+        /* Holds the value of uart config reg */
+        unsigned int U2MODEvalue;
+        /* Holds the information regarding uart
+        TX & RX interrupt modes */
+        unsigned int U2STAvalue;
+        CloseI2C();
+        /* Turn off UART1module */
+        CloseUART2();
+        /* Configure uart1 transmit interrupt */
+        ConfigIntUART2(  UART_TX_INT_DIS & UART_TX_INT_PR2);
+        /* Configure UART1 module to transmit 8 bit data with one stopbit. Also Enable loopback mode  */
+        baudvalue = 15;//129;  //9600
+        U2MODEvalue = UART_EN & UART_IDLE_CON &
+                      UART_DIS_WAKE & UART_DIS_LOOPBACK  &
+                      UART_EN_ABAUD & UART_NO_PAR_8BIT  &
+                      UART_1STOPBIT;
+        U2STAvalue  = UART_INT_TX_BUF_EMPTY  &
+                      UART_TX_PIN_NORMAL &
+                      UART_TX_ENABLE & UART_INT_RX_3_4_FUL &
+                      UART_ADR_DETECT_DIS &
+                      UART_RX_OVERRUN_CLEAR;
+        unsigned int I2C_config1,I2C_config2;
+        I2C_config1 = (I2C_ON & I2C_IDLE_CON & I2C_CLK_HLD &
+                 I2C_IPMI_DIS & I2C_7BIT_ADD &
+                 I2C_SLW_DIS & I2C_SM_DIS &
+                 I2C_GCALL_DIS & I2C_STR_EN &
+                 I2C_ACK & I2C_ACK_EN & I2C_RCV_EN &
+                 I2C_STOP_DIS & I2C_RESTART_EN &
+                 I2C_START_DIS);
+        I2C_config2 = 381;
+        ConfigIntI2C(MI2C_INT_OFF & SI2C_INT_OFF);
+        OpenI2C(I2C_config1,I2C_config2);
+        OpenUART2(U2MODEvalue, U2STAvalue, baudvalue);
+
+        MPU6050(MPU6050_ADDRESS_AD0_LOW);
+        sprintf(Buf,"Initialize MPU6050\n\0");
+        /* Load transmit buffer and transmit the same till null character is encountered */
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+        MPU6050_initialize();
+
+        unsigned char MPU6050_ID = MPU6050_getDeviceID();
+
+        sprintf(Buf,"Testing device connections...\n\0");
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"MPU6050_ID = 0x%X\n",MPU6050_ID);
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+
+        sprintf(Buf,MPU6050_testConnection() ? "MPU6050 connection successful\r\n" :
+            "MPU6050 connection failed\r\n");
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        if (!MPU6050_testConnection())
+            continue;
+
+        sprintf(Buf,"Reading offset\n");
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Xaccel= %d\n",MPU6050_getXAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Yaccel= %d\n",MPU6050_getYAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Zaccel= %d\n",MPU6050_getZAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Xgyro= %d\n",MPU6050_getXGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Ygyro= %d\n",MPU6050_getYGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Zgyro= %d\n",MPU6050_getZGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        MPU6050_setXGyroOffset(220);
+        MPU6050_setYGyroOffset(76);
+        MPU6050_setZGyroOffset(-85);
+
+        sprintf(Buf,"Reading Updated offset\n");
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Xaccel= %d\n",MPU6050_getXAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Yaccel= %d\n",MPU6050_getYAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Zaccel= %d\n",MPU6050_getZAccelOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Xgyro= %d\n",MPU6050_getXGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Ygyro= %d\n",MPU6050_getYGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        sprintf(Buf,"Zgyro= %d\n",MPU6050_getZGyroOffset());
+        putsUART2 ((unsigned int *)Buf);
+        /* Wait for  transmission to complete */
+        while(BusyUART2());
+
+        MPU6050_setSleepEnabled(false);
+        while (true) {
+           // Read raw accel/gyro measurements from device
+            MPU6050_getMotion6(&ax, &ay, &az, &gx, &gy, &gz);
+
+            // Display tab-separated accel/gyro x/y/z values
+            sprintf(Buf,"a/g:\t%d\t%d\t%d\t%d\t%d\t%d\r\n", ax, ay, az, gx, gy, gz);
+            putsUART2 ((unsigned int *)Buf);
+            /* Wait for  transmission to complete */
+            while(BusyUART2());
+            // Blink LED to indicate activity
+            LATCbits.LATC14 ^= 1;
+
+            delay_ms(25);
+            delay_ms(25);
+        }
+        //CloseUART2();
+
+    }
+    return 0;
+}
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/Makefile b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/Makefile
new file mode 100644
index 00000000..fca8e2cc
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/Makefile
@@ -0,0 +1,113 @@
+#
+#  There exist several targets which are by default empty and which can be 
+#  used for execution of your targets. These targets are usually executed 
+#  before and after some main targets. They are: 
+#
+#     .build-pre:              called before 'build' target
+#     .build-post:             called after 'build' target
+#     .clean-pre:              called before 'clean' target
+#     .clean-post:             called after 'clean' target
+#     .clobber-pre:            called before 'clobber' target
+#     .clobber-post:           called after 'clobber' target
+#     .all-pre:                called before 'all' target
+#     .all-post:               called after 'all' target
+#     .help-pre:               called before 'help' target
+#     .help-post:              called after 'help' target
+#
+#  Targets beginning with '.' are not intended to be called on their own.
+#
+#  Main targets can be executed directly, and they are:
+#  
+#     build                    build a specific configuration
+#     clean                    remove built files from a configuration
+#     clobber                  remove all built files
+#     all                      build all configurations
+#     help                     print help mesage
+#  
+#  Targets .build-impl, .clean-impl, .clobber-impl, .all-impl, and
+#  .help-impl are implemented in nbproject/makefile-impl.mk.
+#
+#  Available make variables:
+#
+#     CND_BASEDIR                base directory for relative paths
+#     CND_DISTDIR                default top distribution directory (build artifacts)
+#     CND_BUILDDIR               default top build directory (object files, ...)
+#     CONF                       name of current configuration
+#     CND_ARTIFACT_DIR_${CONF}   directory of build artifact (current configuration)
+#     CND_ARTIFACT_NAME_${CONF}  name of build artifact (current configuration)
+#     CND_ARTIFACT_PATH_${CONF}  path to build artifact (current configuration)
+#     CND_PACKAGE_DIR_${CONF}    directory of package (current configuration)
+#     CND_PACKAGE_NAME_${CONF}   name of package (current configuration)
+#     CND_PACKAGE_PATH_${CONF}   path to package (current configuration)
+#
+# NOCDDL
+
+
+# Environment 
+MKDIR=mkdir
+CP=cp
+CCADMIN=CCadmin
+RANLIB=ranlib
+
+
+# build
+build: .build-post
+
+.build-pre:
+# Add your pre 'build' code here...
+
+.build-post: .build-impl
+# Add your post 'build' code here...
+
+
+# clean
+clean: .clean-post
+
+.clean-pre:
+# Add your pre 'clean' code here...
+# WARNING: the IDE does not call this target since it takes a long time to
+# simply run make. Instead, the IDE removes the configuration directories
+# under build and dist directly without calling make.
+# This target is left here so people can do a clean when running a clean
+# outside the IDE.
+
+.clean-post: .clean-impl
+# Add your post 'clean' code here...
+
+
+# clobber
+clobber: .clobber-post
+
+.clobber-pre:
+# Add your pre 'clobber' code here...
+
+.clobber-post: .clobber-impl
+# Add your post 'clobber' code here...
+
+
+# all
+all: .all-post
+
+.all-pre:
+# Add your pre 'all' code here...
+
+.all-post: .all-impl
+# Add your post 'all' code here...
+
+
+# help
+help: .help-post
+
+.help-pre:
+# Add your pre 'help' code here...
+
+.help-post: .help-impl
+# Add your post 'help' code here...
+
+
+
+# include project implementation makefile
+include nbproject/Makefile-impl.mk
+
+# include project make variables
+include nbproject/Makefile-variables.mk
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-default.mk b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-default.mk
new file mode 100644
index 00000000..11a69249
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-default.mk
@@ -0,0 +1,188 @@
+#
+# Generated Makefile - do not edit!
+#
+# Edit the Makefile in the project folder instead (../Makefile). Each target
+# has a -pre and a -post target defined where you can add customized code.
+#
+# This makefile implements configuration specific macros and targets.
+
+
+# Include project Makefile
+ifeq "${IGNORE_LOCAL}" "TRUE"
+# do not include local makefile. User is passing all local related variables already
+else
+include Makefile
+# Include makefile containing local settings
+ifeq "$(wildcard nbproject/Makefile-local-default.mk)" "nbproject/Makefile-local-default.mk"
+include nbproject/Makefile-local-default.mk
+endif
+endif
+
+# Environment
+MKDIR=mkdir -p
+RM=rm -f 
+MV=mv 
+CP=cp 
+
+# Macros
+CND_CONF=default
+ifeq ($(TYPE_IMAGE), DEBUG_RUN)
+IMAGE_TYPE=debug
+OUTPUT_SUFFIX=elf
+DEBUGGABLE_SUFFIX=elf
+FINAL_IMAGE=dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}
+else
+IMAGE_TYPE=production
+OUTPUT_SUFFIX=hex
+DEBUGGABLE_SUFFIX=elf
+FINAL_IMAGE=dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}
+endif
+
+ifeq ($(COMPARE_BUILD), true)
+COMPARISON_BUILD=-mafrlcsj
+else
+COMPARISON_BUILD=
+endif
+
+ifdef SUB_IMAGE_ADDRESS
+SUB_IMAGE_ADDRESS_COMMAND=--image-address $(SUB_IMAGE_ADDRESS)
+else
+SUB_IMAGE_ADDRESS_COMMAND=
+endif
+
+# Object Directory
+OBJECTDIR=build/${CND_CONF}/${IMAGE_TYPE}
+
+# Distribution Directory
+DISTDIR=dist/${CND_CONF}/${IMAGE_TYPE}
+
+# Source Files Quoted if spaced
+SOURCEFILES_QUOTED_IF_SPACED=MPU6050_example_main.c I2Cdev.c MPU6050.c
+
+# Object Files Quoted if spaced
+OBJECTFILES_QUOTED_IF_SPACED=${OBJECTDIR}/MPU6050_example_main.o ${OBJECTDIR}/I2Cdev.o ${OBJECTDIR}/MPU6050.o
+POSSIBLE_DEPFILES=${OBJECTDIR}/MPU6050_example_main.o.d ${OBJECTDIR}/I2Cdev.o.d ${OBJECTDIR}/MPU6050.o.d
+
+# Object Files
+OBJECTFILES=${OBJECTDIR}/MPU6050_example_main.o ${OBJECTDIR}/I2Cdev.o ${OBJECTDIR}/MPU6050.o
+
+# Source Files
+SOURCEFILES=MPU6050_example_main.c I2Cdev.c MPU6050.c
+
+
+CFLAGS=
+ASFLAGS=
+LDLIBSOPTIONS=
+
+############# Tool locations ##########################################
+# If you copy a project from one host to another, the path where the  #
+# compiler is installed may be different.                             #
+# If you open this project with MPLAB X in the new host, this         #
+# makefile will be regenerated and the paths will be corrected.       #
+#######################################################################
+# fixDeps replaces a bunch of sed/cat/printf statements that slow down the build
+FIXDEPS=fixDeps
+
+.build-conf:  ${BUILD_SUBPROJECTS}
+ifneq ($(INFORMATION_MESSAGE), )
+	@echo $(INFORMATION_MESSAGE)
+endif
+	${MAKE}  -f nbproject/Makefile-default.mk dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}
+
+MP_PROCESSOR_OPTION=30F4013
+MP_LINKER_FILE_OPTION=,--script=p30F4013.gld
+# ------------------------------------------------------------------------------------
+# Rules for buildStep: compile
+ifeq ($(TYPE_IMAGE), DEBUG_RUN)
+${OBJECTDIR}/MPU6050_example_main.o: MPU6050_example_main.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/MPU6050_example_main.o.d 
+	@${RM} ${OBJECTDIR}/MPU6050_example_main.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  MPU6050_example_main.c  -o ${OBJECTDIR}/MPU6050_example_main.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/MPU6050_example_main.o.d"      -g -D__DEBUG -D__MPLAB_DEBUGGER_PK3=1    -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/MPU6050_example_main.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+${OBJECTDIR}/I2Cdev.o: I2Cdev.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/I2Cdev.o.d 
+	@${RM} ${OBJECTDIR}/I2Cdev.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  I2Cdev.c  -o ${OBJECTDIR}/I2Cdev.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/I2Cdev.o.d"      -g -D__DEBUG -D__MPLAB_DEBUGGER_PK3=1    -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/I2Cdev.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+${OBJECTDIR}/MPU6050.o: MPU6050.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/MPU6050.o.d 
+	@${RM} ${OBJECTDIR}/MPU6050.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  MPU6050.c  -o ${OBJECTDIR}/MPU6050.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/MPU6050.o.d"      -g -D__DEBUG -D__MPLAB_DEBUGGER_PK3=1    -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/MPU6050.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+else
+${OBJECTDIR}/MPU6050_example_main.o: MPU6050_example_main.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/MPU6050_example_main.o.d 
+	@${RM} ${OBJECTDIR}/MPU6050_example_main.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  MPU6050_example_main.c  -o ${OBJECTDIR}/MPU6050_example_main.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/MPU6050_example_main.o.d"        -g -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/MPU6050_example_main.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+${OBJECTDIR}/I2Cdev.o: I2Cdev.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/I2Cdev.o.d 
+	@${RM} ${OBJECTDIR}/I2Cdev.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  I2Cdev.c  -o ${OBJECTDIR}/I2Cdev.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/I2Cdev.o.d"        -g -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/I2Cdev.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+${OBJECTDIR}/MPU6050.o: MPU6050.c  nbproject/Makefile-${CND_CONF}.mk
+	@${MKDIR} "${OBJECTDIR}" 
+	@${RM} ${OBJECTDIR}/MPU6050.o.d 
+	@${RM} ${OBJECTDIR}/MPU6050.o 
+	${MP_CC} $(MP_EXTRA_CC_PRE)  MPU6050.c  -o ${OBJECTDIR}/MPU6050.o  -c -mcpu=$(MP_PROCESSOR_OPTION)  -MMD -MF "${OBJECTDIR}/MPU6050.o.d"        -g -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -O0 -msmart-io=1 -Wall -msfr-warn=off  
+	@${FIXDEPS} "${OBJECTDIR}/MPU6050.o.d" $(SILENT)  -rsi ${MP_CC_DIR}../ 
+	
+endif
+
+# ------------------------------------------------------------------------------------
+# Rules for buildStep: assemble
+ifeq ($(TYPE_IMAGE), DEBUG_RUN)
+else
+endif
+
+# ------------------------------------------------------------------------------------
+# Rules for buildStep: assemblePreproc
+ifeq ($(TYPE_IMAGE), DEBUG_RUN)
+else
+endif
+
+# ------------------------------------------------------------------------------------
+# Rules for buildStep: link
+ifeq ($(TYPE_IMAGE), DEBUG_RUN)
+dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}: ${OBJECTFILES}  nbproject/Makefile-${CND_CONF}.mk    
+	@${MKDIR} dist/${CND_CONF}/${IMAGE_TYPE} 
+	${MP_CC} $(MP_EXTRA_LD_PRE)  -o dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}  ${OBJECTFILES_QUOTED_IF_SPACED}      -mcpu=$(MP_PROCESSOR_OPTION)        -D__DEBUG -D__MPLAB_DEBUGGER_PK3=1  -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99  -mreserve=data@0x800:0x81F -mreserve=data@0x820:0x821 -mreserve=data@0x822:0x823 -mreserve=data@0x824:0x84F   -Wl,,,--defsym=__MPLAB_BUILD=1,--defsym=__MPLAB_DEBUG=1,--defsym=__DEBUG=1,--defsym=__MPLAB_DEBUGGER_PK3=1,$(MP_LINKER_FILE_OPTION),--stack=16,--check-sections,--data-init,--pack-data,--handles,--isr,--no-gc-sections,--fill-upper=0,--stackguard=16,--no-force-link,--smart-io,-Map="${DISTDIR}/${PROJECTNAME}.${IMAGE_TYPE}.map",--report-mem,--memorysummary,dist/${CND_CONF}/${IMAGE_TYPE}/memoryfile.xml$(MP_EXTRA_LD_POST) 
+	
+else
+dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}: ${OBJECTFILES}  nbproject/Makefile-${CND_CONF}.mk   
+	@${MKDIR} dist/${CND_CONF}/${IMAGE_TYPE} 
+	${MP_CC} $(MP_EXTRA_LD_PRE)  -o dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${DEBUGGABLE_SUFFIX}  ${OBJECTFILES_QUOTED_IF_SPACED}      -mcpu=$(MP_PROCESSOR_OPTION)        -omf=elf -DXPRJ_default=$(CND_CONF)  -legacy-libc  $(COMPARISON_BUILD)  --std=gnu99 -Wl,,,--defsym=__MPLAB_BUILD=1,$(MP_LINKER_FILE_OPTION),--stack=16,--check-sections,--data-init,--pack-data,--handles,--isr,--no-gc-sections,--fill-upper=0,--stackguard=16,--no-force-link,--smart-io,-Map="${DISTDIR}/${PROJECTNAME}.${IMAGE_TYPE}.map",--report-mem,--memorysummary,dist/${CND_CONF}/${IMAGE_TYPE}/memoryfile.xml$(MP_EXTRA_LD_POST) 
+	${MP_CC_DIR}/xc16-bin2hex dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${DEBUGGABLE_SUFFIX} -a  -omf=elf  
+	
+endif
+
+
+# Subprojects
+.build-subprojects:
+
+
+# Subprojects
+.clean-subprojects:
+
+# Clean Targets
+.clean-conf: ${CLEAN_SUBPROJECTS}
+	${RM} -r build/default
+	${RM} -r dist/default
+
+# Enable dependency checking
+.dep.inc: .depcheck-impl
+
+DEPFILES=$(shell "${PATH_TO_IDE_BIN}"mplabwildcard ${POSSIBLE_DEPFILES})
+ifneq (${DEPFILES},)
+include ${DEPFILES}
+endif
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-genesis.properties b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-genesis.properties
new file mode 100644
index 00000000..b83100c2
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-genesis.properties
@@ -0,0 +1,9 @@
+#
+#Wed Apr 26 15:57:55 CST 2017
+default.com-microchip-mplab-nbide-toolchainXC16-XC16LanguageToolchain.md5=10deee1b358b9eb8b4aaaeb9dce00420
+default.languagetoolchain.dir=/opt/microchip/xc16/v1.31/bin
+configurations-xml=fd1da04a6257bc2861900a03a85b49c1
+com-microchip-mplab-nbide-embedded-makeproject-MakeProject.md5=68c66d83550b716fa3e84319671e802c
+default.languagetoolchain.version=1.31
+host.platform=linux
+conf.ids=default
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-impl.mk b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-impl.mk
new file mode 100644
index 00000000..5b2593af
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-impl.mk
@@ -0,0 +1,69 @@
+#
+# Generated Makefile - do not edit!
+#
+# Edit the Makefile in the project folder instead (../Makefile). Each target
+# has a pre- and a post- target defined where you can add customization code.
+#
+# This makefile implements macros and targets common to all configurations.
+#
+# NOCDDL
+
+
+# Building and Cleaning subprojects are done by default, but can be controlled with the SUB
+# macro. If SUB=no, subprojects will not be built or cleaned. The following macro
+# statements set BUILD_SUB-CONF and CLEAN_SUB-CONF to .build-reqprojects-conf
+# and .clean-reqprojects-conf unless SUB has the value 'no'
+SUB_no=NO
+SUBPROJECTS=${SUB_${SUB}}
+BUILD_SUBPROJECTS_=.build-subprojects
+BUILD_SUBPROJECTS_NO=
+BUILD_SUBPROJECTS=${BUILD_SUBPROJECTS_${SUBPROJECTS}}
+CLEAN_SUBPROJECTS_=.clean-subprojects
+CLEAN_SUBPROJECTS_NO=
+CLEAN_SUBPROJECTS=${CLEAN_SUBPROJECTS_${SUBPROJECTS}}
+
+
+# Project Name
+PROJECTNAME=MPU6050_example.X
+
+# Active Configuration
+DEFAULTCONF=default
+CONF=${DEFAULTCONF}
+
+# All Configurations
+ALLCONFS=default 
+
+
+# build
+.build-impl: .build-pre
+	${MAKE} -f nbproject/Makefile-${CONF}.mk SUBPROJECTS=${SUBPROJECTS} .build-conf
+
+
+# clean
+.clean-impl: .clean-pre
+	${MAKE} -f nbproject/Makefile-${CONF}.mk SUBPROJECTS=${SUBPROJECTS} .clean-conf
+
+# clobber
+.clobber-impl: .clobber-pre .depcheck-impl
+	    ${MAKE} SUBPROJECTS=${SUBPROJECTS} CONF=default clean
+
+
+
+# all
+.all-impl: .all-pre .depcheck-impl
+	    ${MAKE} SUBPROJECTS=${SUBPROJECTS} CONF=default build
+
+
+
+# dependency checking support
+.depcheck-impl:
+#	@echo "# This code depends on make tool being used" >.dep.inc
+#	@if [ -n "${MAKE_VERSION}" ]; then \
+#	    echo "DEPFILES=\$$(wildcard \$$(addsuffix .d, \$${OBJECTFILES}))" >>.dep.inc; \
+#	    echo "ifneq (\$${DEPFILES},)" >>.dep.inc; \
+#	    echo "include \$${DEPFILES}" >>.dep.inc; \
+#	    echo "endif" >>.dep.inc; \
+#	else \
+#	    echo ".KEEP_STATE:" >>.dep.inc; \
+#	    echo ".KEEP_STATE_FILE:.make.state.\$${CONF}" >>.dep.inc; \
+#	fi
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-local-default.mk b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-local-default.mk
new file mode 100644
index 00000000..867c8d36
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-local-default.mk
@@ -0,0 +1,36 @@
+#
+# Generated Makefile - do not edit!
+#
+#
+# This file contains information about the location of compilers and other tools.
+# If you commmit this file into your revision control server, you will be able to 
+# to checkout the project and build it from the command line with make. However,
+# if more than one person works on the same project, then this file might show
+# conflicts since different users are bound to have compilers in different places.
+# In that case you might choose to not commit this file and let MPLAB X recreate this file
+# for each user. The disadvantage of not commiting this file is that you must run MPLAB X at
+# least once so the file gets created and the project can be built. Finally, you can also
+# avoid using this file at all if you are only building from the command line with make.
+# You can invoke make with the values of the macros:
+# $ makeMP_CC="/opt/microchip/mplabc30/v3.30c/bin/pic30-gcc" ...  
+#
+PATH_TO_IDE_BIN=/opt/microchip/mplabx/v3.60/mplab_ide/platform/../mplab_ide/modules/../../bin/
+# Adding MPLAB X bin directory to path.
+PATH:=/opt/microchip/mplabx/v3.60/mplab_ide/platform/../mplab_ide/modules/../../bin/:$(PATH)
+# Path to java used to run MPLAB X when this makefile was created
+MP_JAVA_PATH="/opt/microchip/mplabx/v3.60/sys/java/jre1.8.0_121/bin/"
+OS_CURRENT="$(shell uname -s)"
+MP_CC="/opt/microchip/xc16/v1.31/bin/xc16-gcc"
+# MP_CPPC is not defined
+# MP_BC is not defined
+MP_AS="/opt/microchip/xc16/v1.31/bin/xc16-as"
+MP_LD="/opt/microchip/xc16/v1.31/bin/xc16-ld"
+MP_AR="/opt/microchip/xc16/v1.31/bin/xc16-ar"
+DEP_GEN=${MP_JAVA_PATH}java -jar "/opt/microchip/mplabx/v3.60/mplab_ide/platform/../mplab_ide/modules/../../bin/extractobjectdependencies.jar"
+MP_CC_DIR="/opt/microchip/xc16/v1.31/bin"
+# MP_CPPC_DIR is not defined
+# MP_BC_DIR is not defined
+MP_AS_DIR="/opt/microchip/xc16/v1.31/bin"
+MP_LD_DIR="/opt/microchip/xc16/v1.31/bin"
+MP_AR_DIR="/opt/microchip/xc16/v1.31/bin"
+# MP_BC_DIR is not defined
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-variables.mk b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-variables.mk
new file mode 100644
index 00000000..a8ce072f
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Makefile-variables.mk
@@ -0,0 +1,13 @@
+#
+# Generated - do not edit!
+#
+# NOCDDL
+#
+CND_BASEDIR=`pwd`
+# default configuration
+CND_ARTIFACT_DIR_default=dist/default/production
+CND_ARTIFACT_NAME_default=MPU6050_example.X.production.hex
+CND_ARTIFACT_PATH_default=dist/default/production/MPU6050_example.X.production.hex
+CND_PACKAGE_DIR_default=${CND_DISTDIR}/default/package
+CND_PACKAGE_NAME_default=mpu6050example.x.tar
+CND_PACKAGE_PATH_default=${CND_DISTDIR}/default/package/mpu6050example.x.tar
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Package-default.bash b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Package-default.bash
new file mode 100644
index 00000000..552f66ff
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/Package-default.bash
@@ -0,0 +1,73 @@
+#!/bin/bash -x
+
+#
+# Generated - do not edit!
+#
+
+# Macros
+TOP=`pwd`
+CND_CONF=default
+CND_DISTDIR=dist
+TMPDIR=build/${CND_CONF}/${IMAGE_TYPE}/tmp-packaging
+TMPDIRNAME=tmp-packaging
+OUTPUT_PATH=dist/${CND_CONF}/${IMAGE_TYPE}/MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}
+OUTPUT_BASENAME=MPU6050_example.X.${IMAGE_TYPE}.${OUTPUT_SUFFIX}
+PACKAGE_TOP_DIR=mpu6050example.x/
+
+# Functions
+function checkReturnCode
+{
+    rc=$?
+    if [ $rc != 0 ]
+    then
+        exit $rc
+    fi
+}
+function makeDirectory
+# $1 directory path
+# $2 permission (optional)
+{
+    mkdir -p "$1"
+    checkReturnCode
+    if [ "$2" != "" ]
+    then
+      chmod $2 "$1"
+      checkReturnCode
+    fi
+}
+function copyFileToTmpDir
+# $1 from-file path
+# $2 to-file path
+# $3 permission
+{
+    cp "$1" "$2"
+    checkReturnCode
+    if [ "$3" != "" ]
+    then
+        chmod $3 "$2"
+        checkReturnCode
+    fi
+}
+
+# Setup
+cd "${TOP}"
+mkdir -p ${CND_DISTDIR}/${CND_CONF}/package
+rm -rf ${TMPDIR}
+mkdir -p ${TMPDIR}
+
+# Copy files and create directories and links
+cd "${TOP}"
+makeDirectory ${TMPDIR}/mpu6050example.x/bin
+copyFileToTmpDir "${OUTPUT_PATH}" "${TMPDIR}/${PACKAGE_TOP_DIR}bin/${OUTPUT_BASENAME}" 0755
+
+
+# Generate tar file
+cd "${TOP}"
+rm -f ${CND_DISTDIR}/${CND_CONF}/package/mpu6050example.x.tar
+cd ${TMPDIR}
+tar -vcf ../../../../${CND_DISTDIR}/${CND_CONF}/package/mpu6050example.x.tar *
+checkReturnCode
+
+# Cleanup
+cd "${TOP}"
+rm -rf ${TMPDIR}
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/configurations.xml b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/configurations.xml
new file mode 100644
index 00000000..6fd8b07f
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/configurations.xml
@@ -0,0 +1,549 @@
+
+
+  
+    
+      I2Cdev.h
+      MPU6050.h
+    
+    
+    
+    
+      MPU6050_example_main.c
+      I2Cdev.c
+      MPU6050.c
+    
+    
+      Makefile
+    
+  
+  Makefile
+  
+    
+      
+        localhost
+        dsPIC30F4013
+        
+        
+        PICkit3PlatformTool
+        XC16
+        1.31
+        2
+      
+      
+        
+          
+          
+        
+        
+        
+        
+          false
+          false
+          
+        
+        
+        
+      
+      
+        false
+        
+        false
+        
+        false
+        false
+        false
+      
+      
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+      
+      
+        
+      
+      
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+      
+      
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+      
+      
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+      
+      
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+        
+      
+    
+  
+
diff --git a/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/project.xml b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/project.xml
new file mode 100644
index 00000000..3230bc50
--- /dev/null
+++ b/dsPIC30F/MPU6050/Examples/MPU6050_example.X/nbproject/project.xml
@@ -0,0 +1,17 @@
+
+
+    com.microchip.mplab.nbide.embedded.makeproject
+    
+        
+            MPU6050_example
+            04e5589e-1a03-434e-ace3-9ef3c9c9d958
+            0
+            c
+            
+            h
+            
+            ISO-8859-1
+            
+        
+    
+
diff --git a/dsPIC30F/MPU6050/MPU6050.c b/dsPIC30F/MPU6050/MPU6050.c
new file mode 100644
index 00000000..2683529a
--- /dev/null
+++ b/dsPIC30F/MPU6050/MPU6050.c
@@ -0,0 +1,3141 @@
+// 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 
+// 11/28/2014 by Marton Sebok 
+//
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ...        - ongoing debug release
+//     2014-11-28 - ported to PIC18 peripheral library from Arduino code
+
+// 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
+Copyright (c) 2014 Marton Sebok
+
+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"
+
+MPU6050_t mpu6050;
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see MPU6050_DEFAULT_ADDRESS
+ * @see MPU6050_ADDRESS_AD0_LOW
+ * @see MPU6050_ADDRESS_AD0_HIGH
+ */
+void MPU6050(uint8_t address) {
+    mpu6050.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() {
+    MPU6050_setClockSource(MPU6050_CLOCK_PLL_XGYRO);
+    MPU6050_setFullScaleGyroRange(MPU6050_GYRO_FS_250);
+    MPU6050_setFullScaleAccelRange(MPU6050_ACCEL_FS_2);
+    MPU6050_setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+}
+
+/** 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() {
+    return MPU6050_getDeviceID() == 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(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_SMPLRT_DIV, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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.
+ *
+ * 
+ * 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]
+ * 
+ * + * @return FSYNC configuration value + */ +uint8_t MPU6050_getExternalFrameSync() { + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ *          |   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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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. + * + *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ *    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.
+ * 
+ * + *
+ * 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
+ * 
+ * + * @return Current high-pass filter configuration + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +uint8_t MPU6050_getDHPFMode() { + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_FF_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_FF_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ZRMOT_THR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_ZRMOT_DUR, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current temperature FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getTempFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getXGyroFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getYGyroFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getZGyroFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getAccelFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave2FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave1FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050_getSlave0FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU6050_RA_MST_CTRL + */ +bool MPU6050_getSlave3FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @return Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +uint8_t MPU6050_getMasterClockSpeed() { + I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_ADDR, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_REG, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_SLV4_DI, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer); + return mpu6050.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) { + MPU6050_getMotion6(ax, ay, az, gx, gy, gz); + // TODO: magnetometer integration +} +/** 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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, mpu6050.buffer); + *ax = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *ay = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *az = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.buffer[5]; + *gx = (((int16_t)mpu6050.buffer[8]) << 8) | mpu6050.buffer[9]; + *gy = (((int16_t)mpu6050.buffer[10]) << 8) | mpu6050.buffer[11]; + *gz = (((int16_t)mpu6050.buffer[12]) << 8) | mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, mpu6050.buffer); + *x = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *y = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *z = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_TEMP_OUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.devAddr, MPU6050_RA_GYRO_XOUT_H, 6, mpu6050.buffer); + *x = (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1]; + *y = (((int16_t)mpu6050.buffer[2]) << 8) | mpu6050.buffer[3]; + *z = (((int16_t)mpu6050.buffer[4]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_XOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_YOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, mpu6050.buffer); + return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, mpu6050.buffer); + return (((uint16_t)mpu6050.buffer[0]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, mpu6050.buffer); + return (((uint32_t)mpu6050.buffer[0]) << 24) | (((uint32_t)mpu6050.buffer[1]) << 16) | (((uint16_t)mpu6050.buffer[2]) << 8) | mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * 
+ * + * 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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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: + * + *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * 
+ * + * 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(mpu6050.devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, mpu6050.buffer); + return mpu6050.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(mpu6050.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 mpu6050.buffer is disabled. The FIFO mpu6050.buffer + * cannot be written to or read from while disabled. The FIFO mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, mpu6050.buffer); + return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, mpu6050.buffer); + return mpu6050.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: + * + *
+ * 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
+ * 
+ * + * @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(mpu6050.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: + * + *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * 
+ *
+ * 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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, mpu6050.buffer);
+    return mpu6050.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(mpu6050.devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO mpu6050.buffer size.
+ * This value indicates the number of bytes stored in the FIFO mpu6050.buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO mpu6050.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 mpu6050.buffer size
+ */
+uint16_t MPU6050_getFIFOCount() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_FIFO_COUNTH, 2, mpu6050.buffer);
+    return (((uint16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO mpu6050.buffer.
+ * This register is used to read and write data from the FIFO mpu6050.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 mpu6050.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 mpu6050.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 mpu6050.buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO mpu6050.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 mpu6050.buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO mpu6050.buffer
+ */
+uint8_t MPU6050_getFIFOByte() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_FIFO_R_W, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_getFIFOBytes(uint8_t *data, uint8_t length) {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO mpu6050.buffer.
+ * @see getFIFOByte()
+ * @see MPU6050_RA_FIFO_R_W
+ */
+void MPU6050_setFIFOByte(uint8_t data) {
+    I2Cdev_writeByte(mpu6050.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(mpu6050.devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, mpu6050.buffer);
+    return mpu6050.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(mpu6050.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(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setOTPBankValid(bool enabled) {
+    I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU6050_getXGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setXGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU6050_getYGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setYGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU6050_getZGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setZGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.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(mpu6050.devAddr, MPU6050_RA_X_FINE_GAIN, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setXFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU6050_getYFineGain() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_Y_FINE_GAIN, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setYFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU6050_getZFineGain() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_Z_FINE_GAIN, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setZFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU6050_getXAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_XA_OFFS_H, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setXAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU6050_getYAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_YA_OFFS_H, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setYAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU6050_getZAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_ZA_OFFS_H, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setZAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU6050_getXGyroOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_XG_OFFS_USRH, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setXGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU6050_getYGyroOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_YG_OFFS_USRH, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setYGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU6050_getZGyroOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, mpu6050.buffer);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void MPU6050_setZGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, MPU6050_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU6050_getIntPLLReadyEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setIntPLLReadyEnabled(bool enabled) {
+    I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU6050_getIntDMPEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setIntDMPEnabled(bool enabled) {
+    I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU6050_getDMPInt5Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt4Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt3Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt2Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt1Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getDMPInt0Status() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU6050_getIntPLLReadyStatus() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+bool MPU6050_getIntDMPStatus() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU6050_getDMPEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setDMPEnabled(bool enabled) {
+    I2Cdev_writeBit(mpu6050.devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU6050_resetDMP() {
+    I2Cdev_writeBit(mpu6050.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(mpu6050.devAddr, MPU6050_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU6050_setMemoryStartAddress(uint8_t address) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU6050_readMemoryByte() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_MEM_R_W, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_writeMemoryByte(uint8_t data) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_MEM_R_W, data);
+}
+void MPU6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    MPU6050_setMemoryBank(bank, false, false);
+    MPU6050_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(mpu6050.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++;
+            MPU6050_setMemoryBank(bank, false, false);
+            MPU6050_setMemoryStartAddress(address);
+        }
+    }
+}
+/*bool MPU6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+    MPU6050_setMemoryBank(bank, false, false);
+    MPU6050_setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer;
+    uint8_t *progBuffer;
+    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(mpu6050.devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            MPU6050_setMemoryBank(bank, false, false);
+            MPU6050_setMemoryStartAddress(address);
+            I2Cdev_readBytes(mpu6050.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++;
+            MPU6050_setMemoryBank(bank, false, false);
+            MPU6050_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 MPU6050_writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
+    uint8_t *progBuffer, success, special;
+    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 = MPU6050_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(mpu6050.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 MPU6050_writeDMPConfigurationSet(data, dataSize, true);
+}*/
+
+// DMP_CFG_1 register
+
+uint8_t MPU6050_getDMPConfig1() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_1, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setDMPConfig1(uint8_t config) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU6050_getDMPConfig2() {
+    I2Cdev_readByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_2, mpu6050.buffer);
+    return mpu6050.buffer[0];
+}
+void MPU6050_setDMPConfig2(uint8_t config) {
+    I2Cdev_writeByte(mpu6050.devAddr, MPU6050_RA_DMP_CFG_2, config);
+}
\ No newline at end of file
diff --git a/dsPIC30F/MPU6050/MPU6050.h b/dsPIC30F/MPU6050/MPU6050.h
new file mode 100644
index 00000000..4f35e336
--- /dev/null
+++ b/dsPIC30F/MPU6050/MPU6050.h
@@ -0,0 +1,786 @@
+// 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 
+// 11/28/2014 by Marton Sebok 
+//
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ...        - ongoing debug release
+//     2014-11-28 - ported to PIC18 peripheral library from Arduino code
+
+// 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
+Copyright (c) 2014 Marton Sebok
+
+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/I2Cdev.h"
+
+#if ((defined MPU6050_INCLUDE_DMP_MOTIONAPPS20) || (defined MPU6050_INCLUDE_DMP_MOTIONAPPS41))
+    #error DMP is not supported yet
+#endif
+
+#define MPU6050_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU6050_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU6050_DEFAULT_ADDRESS     MPU6050_ADDRESS_AD0_LOW
+
+#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 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
+
+typedef struct MPU6050_t {
+    uint8_t devAddr;
+    uint8_t buffer[14];
+} MPU6050_t;
+
+void MPU6050(uint8_t address);
+
+void MPU6050_initialize();
+bool MPU6050_testConnection();
+
+// AUX_VDDIO register
+uint8_t MPU6050_getAuxVDDIOLevel();
+void MPU6050_setAuxVDDIOLevel(uint8_t level);
+
+// SMPLRT_DIV register
+uint8_t MPU6050_getRate();
+void MPU6050_setRate(uint8_t rate);
+
+// CONFIG register
+uint8_t MPU6050_getExternalFrameSync();
+void MPU6050_setExternalFrameSync(uint8_t sync);
+uint8_t MPU6050_getDLPFMode();
+void MPU6050_setDLPFMode(uint8_t bandwidth);
+
+// GYRO_CONFIG register
+uint8_t MPU6050_getFullScaleGyroRange();
+void MPU6050_setFullScaleGyroRange(uint8_t range);
+
+// ACCEL_CONFIG register
+bool MPU6050_getAccelXSelfTest();
+void MPU6050_setAccelXSelfTest(bool enabled);
+bool MPU6050_getAccelYSelfTest();
+void MPU6050_setAccelYSelfTest(bool enabled);
+bool MPU6050_getAccelZSelfTest();
+void MPU6050_setAccelZSelfTest(bool enabled);
+uint8_t MPU6050_getFullScaleAccelRange();
+void MPU6050_setFullScaleAccelRange(uint8_t range);
+uint8_t MPU6050_getDHPFMode();
+void MPU6050_setDHPFMode(uint8_t mode);
+
+// FF_THR register
+uint8_t MPU6050_getFreefallDetectionThreshold();
+void MPU6050_setFreefallDetectionThreshold(uint8_t threshold);
+
+// FF_DUR register
+uint8_t MPU6050_getFreefallDetectionDuration();
+void MPU6050_setFreefallDetectionDuration(uint8_t duration);
+
+// MOT_THR register
+uint8_t MPU6050_getMotionDetectionThreshold();
+void MPU6050_setMotionDetectionThreshold(uint8_t threshold);
+
+// MOT_DUR register
+uint8_t MPU6050_getMotionDetectionDuration();
+void MPU6050_setMotionDetectionDuration(uint8_t duration);
+
+// ZRMOT_THR register
+uint8_t MPU6050_getZeroMotionDetectionThreshold();
+void MPU6050_setZeroMotionDetectionThreshold(uint8_t threshold);
+
+// ZRMOT_DUR register
+uint8_t MPU6050_getZeroMotionDetectionDuration();
+void MPU6050_setZeroMotionDetectionDuration(uint8_t duration);
+
+// FIFO_EN register
+bool MPU6050_getTempFIFOEnabled();
+void MPU6050_setTempFIFOEnabled(bool enabled);
+bool MPU6050_getXGyroFIFOEnabled();
+void MPU6050_setXGyroFIFOEnabled(bool enabled);
+bool MPU6050_getYGyroFIFOEnabled();
+void MPU6050_setYGyroFIFOEnabled(bool enabled);
+bool MPU6050_getZGyroFIFOEnabled();
+void MPU6050_setZGyroFIFOEnabled(bool enabled);
+bool MPU6050_getAccelFIFOEnabled();
+void MPU6050_setAccelFIFOEnabled(bool enabled);
+bool MPU6050_getSlave2FIFOEnabled();
+void MPU6050_setSlave2FIFOEnabled(bool enabled);
+bool MPU6050_getSlave1FIFOEnabled();
+void MPU6050_setSlave1FIFOEnabled(bool enabled);
+bool MPU6050_getSlave0FIFOEnabled();
+void MPU6050_setSlave0FIFOEnabled(bool enabled);
+
+// I2C_MST_CTRL register
+bool MPU6050_getMultiMasterEnabled();
+void MPU6050_setMultiMasterEnabled(bool enabled);
+bool MPU6050_getWaitForExternalSensorEnabled();
+void MPU6050_setWaitForExternalSensorEnabled(bool enabled);
+bool MPU6050_getSlave3FIFOEnabled();
+void MPU6050_setSlave3FIFOEnabled(bool enabled);
+bool MPU6050_getSlaveReadWriteTransitionEnabled();
+void MPU6050_setSlaveReadWriteTransitionEnabled(bool enabled);
+uint8_t MPU6050_getMasterClockSpeed();
+void MPU6050_setMasterClockSpeed(uint8_t speed);
+
+// I2C_SLV* registers (Slave 0-3)
+uint8_t MPU6050_getSlaveAddress(uint8_t num);
+void MPU6050_setSlaveAddress(uint8_t num, uint8_t address);
+uint8_t MPU6050_getSlaveRegister(uint8_t num);
+void MPU6050_setSlaveRegister(uint8_t num, uint8_t reg);
+bool MPU6050_getSlaveEnabled(uint8_t num);
+void MPU6050_setSlaveEnabled(uint8_t num, bool enabled);
+bool MPU6050_getSlaveWordByteSwap(uint8_t num);
+void MPU6050_setSlaveWordByteSwap(uint8_t num, bool enabled);
+bool MPU6050_getSlaveWriteMode(uint8_t num);
+void MPU6050_setSlaveWriteMode(uint8_t num, bool mode);
+bool MPU6050_getSlaveWordGroupOffset(uint8_t num);
+void MPU6050_setSlaveWordGroupOffset(uint8_t num, bool enabled);
+uint8_t MPU6050_getSlaveDataLength(uint8_t num);
+void MPU6050_setSlaveDataLength(uint8_t num, uint8_t length);
+
+// I2C_SLV* registers (Slave 4)
+uint8_t MPU6050_getSlave4Address();
+void MPU6050_setSlave4Address(uint8_t address);
+uint8_t MPU6050_getSlave4Register();
+void MPU6050_setSlave4Register(uint8_t reg);
+void MPU6050_setSlave4OutputByte(uint8_t data);
+bool MPU6050_getSlave4Enabled();
+void MPU6050_setSlave4Enabled(bool enabled);
+bool MPU6050_getSlave4InterruptEnabled();
+void MPU6050_setSlave4InterruptEnabled(bool enabled);
+bool MPU6050_getSlave4WriteMode();
+void MPU6050_setSlave4WriteMode(bool mode);
+uint8_t MPU6050_getSlave4MasterDelay();
+void MPU6050_setSlave4MasterDelay(uint8_t delay);
+uint8_t MPU6050_getSlate4InputByte();
+
+// I2C_MST_STATUS register
+bool MPU6050_getPassthroughStatus();
+bool MPU6050_getSlave4IsDone();
+bool MPU6050_getLostArbitration();
+bool MPU6050_getSlave4Nack();
+bool MPU6050_getSlave3Nack();
+bool MPU6050_getSlave2Nack();
+bool MPU6050_getSlave1Nack();
+bool MPU6050_getSlave0Nack();
+
+// INT_PIN_CFG register
+bool MPU6050_getInterruptMode();
+void MPU6050_setInterruptMode(bool mode);
+bool MPU6050_getInterruptDrive();
+void MPU6050_setInterruptDrive(bool drive);
+bool MPU6050_getInterruptLatch();
+void MPU6050_setInterruptLatch(bool latch);
+bool MPU6050_getInterruptLatchClear();
+void MPU6050_setInterruptLatchClear(bool clear);
+bool MPU6050_getFSyncInterruptLevel();
+void MPU6050_setFSyncInterruptLevel(bool level);
+bool MPU6050_getFSyncInterruptEnabled();
+void MPU6050_setFSyncInterruptEnabled(bool enabled);
+bool MPU6050_getI2CBypassEnabled();
+void MPU6050_setI2CBypassEnabled(bool enabled);
+bool MPU6050_getClockOutputEnabled();
+void MPU6050_setClockOutputEnabled(bool enabled);
+
+// INT_ENABLE register
+uint8_t MPU6050_getIntEnabled();
+void MPU6050_setIntEnabled(uint8_t enabled);
+bool MPU6050_getIntFreefallEnabled();
+void MPU6050_setIntFreefallEnabled(bool enabled);
+bool MPU6050_getIntMotionEnabled();
+void MPU6050_setIntMotionEnabled(bool enabled);
+bool MPU6050_getIntZeroMotionEnabled();
+void MPU6050_setIntZeroMotionEnabled(bool enabled);
+bool MPU6050_getIntFIFOBufferOverflowEnabled();
+void MPU6050_setIntFIFOBufferOverflowEnabled(bool enabled);
+bool MPU6050_getIntI2CMasterEnabled();
+void MPU6050_setIntI2CMasterEnabled(bool enabled);
+bool MPU6050_getIntDataReadyEnabled();
+void MPU6050_setIntDataReadyEnabled(bool enabled);
+
+// INT_STATUS register
+uint8_t MPU6050_getIntStatus();
+bool MPU6050_getIntFreefallStatus();
+bool MPU6050_getIntMotionStatus();
+bool MPU6050_getIntZeroMotionStatus();
+bool MPU6050_getIntFIFOBufferOverflowStatus();
+bool MPU6050_getIntI2CMasterStatus();
+bool MPU6050_getIntDataReadyStatus();
+
+// ACCEL_*OUT_* registers
+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);
+void MPU6050_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+void MPU6050_getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+int16_t MPU6050_getAccelerationX();
+int16_t MPU6050_getAccelerationY();
+int16_t MPU6050_getAccelerationZ();
+
+// TEMP_OUT_* registers
+int16_t MPU6050_getTemperature();
+
+// GYRO_*OUT_* registers
+void MPU6050_getRotation(int16_t* x, int16_t* y, int16_t* z);
+int16_t MPU6050_getRotationX();
+int16_t MPU6050_getRotationY();
+int16_t MPU6050_getRotationZ();
+
+// EXT_SENS_DATA_* registers
+uint8_t MPU6050_getExternalSensorByte(int position);
+uint16_t MPU6050_getExternalSensorWord(int position);
+uint32_t getExternalSensorDWord(int position);
+
+// MOT_DETECT_STATUS register
+bool MPU6050_getXNegMotionDetected();
+bool MPU6050_getXPosMotionDetected();
+bool MPU6050_getYNegMotionDetected();
+bool MPU6050_getYPosMotionDetected();
+bool MPU6050_getZNegMotionDetected();
+bool MPU6050_getZPosMotionDetected();
+bool MPU6050_getZeroMotionDetected();
+
+// I2C_SLV*_DO register
+void MPU6050_setSlaveOutputByte(uint8_t num, uint8_t data);
+
+// I2C_MST_DELAY_CTRL register
+bool MPU6050_getExternalShadowDelayEnabled();
+void MPU6050_setExternalShadowDelayEnabled(bool enabled);
+bool MPU6050_getSlaveDelayEnabled(uint8_t num);
+void MPU6050_setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+// SIGNAL_PATH_RESET register
+void MPU6050_resetGyroscopePath();
+void MPU6050_resetAccelerometerPath();
+void MPU6050_resetTemperaturePath();
+
+// MOT_DETECT_CTRL register
+uint8_t MPU6050_getAccelerometerPowerOnDelay();
+void MPU6050_setAccelerometerPowerOnDelay(uint8_t delay);
+uint8_t MPU6050_getFreefallDetectionCounterDecrement();
+void MPU6050_setFreefallDetectionCounterDecrement(uint8_t decrement);
+uint8_t MPU6050_getMotionDetectionCounterDecrement();
+void MPU6050_setMotionDetectionCounterDecrement(uint8_t decrement);
+
+// USER_CTRL register
+bool MPU6050_getFIFOEnabled();
+void MPU6050_setFIFOEnabled(bool enabled);
+bool MPU6050_getI2CMasterModeEnabled();
+void MPU6050_setI2CMasterModeEnabled(bool enabled);
+void MPU6050_switchSPIEnabled(bool enabled);
+void MPU6050_resetFIFO();
+void MPU6050_resetI2CMaster();
+void MPU6050_resetSensors();
+
+// PWR_MGMT_1 register
+void MPU6050_reset();
+bool MPU6050_getSleepEnabled();
+void MPU6050_setSleepEnabled(bool enabled);
+bool MPU6050_getWakeCycleEnabled();
+void MPU6050_setWakeCycleEnabled(bool enabled);
+bool MPU6050_getTempSensorEnabled();
+void MPU6050_setTempSensorEnabled(bool enabled);
+uint8_t MPU6050_getClockSource();
+void MPU6050_setClockSource(uint8_t source);
+
+// PWR_MGMT_2 register
+uint8_t MPU6050_getWakeFrequency();
+void MPU6050_setWakeFrequency(uint8_t frequency);
+bool MPU6050_getStandbyXAccelEnabled();
+void MPU6050_setStandbyXAccelEnabled(bool enabled);
+bool MPU6050_getStandbyYAccelEnabled();
+void MPU6050_setStandbyYAccelEnabled(bool enabled);
+bool MPU6050_getStandbyZAccelEnabled();
+void MPU6050_setStandbyZAccelEnabled(bool enabled);
+bool MPU6050_getStandbyXGyroEnabled();
+void MPU6050_setStandbyXGyroEnabled(bool enabled);
+bool MPU6050_getStandbyYGyroEnabled();
+void MPU6050_setStandbyYGyroEnabled(bool enabled);
+bool MPU6050_getStandbyZGyroEnabled();
+void MPU6050_setStandbyZGyroEnabled(bool enabled);
+
+// FIFO_COUNT_* registers
+uint16_t MPU6050_getFIFOCount();
+
+// FIFO_R_W register
+uint8_t MPU6050_getFIFOByte();
+void MPU6050_setFIFOByte(uint8_t data);
+void MPU6050_getFIFOBytes(uint8_t *data, uint8_t length);
+
+// WHO_AM_I register
+uint8_t MPU6050_getDeviceID();
+void MPU6050_setDeviceID(uint8_t id);
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+uint8_t MPU6050_getOTPBankValid();
+void MPU6050_setOTPBankValid(bool enabled);
+int8_t getXGyroOffsetTC();
+void MPU6050_setXGyroOffsetTC(int8_t offset);
+
+// YG_OFFS_TC register
+int8_t getYGyroOffsetTC();
+void MPU6050_setYGyroOffsetTC(int8_t offset);
+
+// ZG_OFFS_TC register
+int8_t getZGyroOffsetTC();
+void MPU6050_setZGyroOffsetTC(int8_t offset);
+
+// X_FINE_GAIN register
+int8_t getXFineGain();
+void MPU6050_setXFineGain(int8_t gain);
+
+// Y_FINE_GAIN register
+int8_t getYFineGain();
+void MPU6050_setYFineGain(int8_t gain);
+
+// Z_FINE_GAIN register
+int8_t getZFineGain();
+void MPU6050_setZFineGain(int8_t gain);
+
+// XA_OFFS_* registers
+int16_t MPU6050_getXAccelOffset();
+void MPU6050_setXAccelOffset(int16_t offset);
+
+// YA_OFFS_* register
+int16_t MPU6050_getYAccelOffset();
+void MPU6050_setYAccelOffset(int16_t offset);
+
+// ZA_OFFS_* register
+int16_t MPU6050_getZAccelOffset();
+void MPU6050_setZAccelOffset(int16_t offset);
+
+// XG_OFFS_USR* registers
+int16_t MPU6050_getXGyroOffset();
+void MPU6050_setXGyroOffset(int16_t offset);
+
+// YG_OFFS_USR* register
+int16_t MPU6050_getYGyroOffset();
+void MPU6050_setYGyroOffset(int16_t offset);
+
+// ZG_OFFS_USR* register
+int16_t MPU6050_getZGyroOffset();
+void MPU6050_setZGyroOffset(int16_t offset);
+
+// INT_ENABLE register (DMP functions)
+bool MPU6050_getIntPLLReadyEnabled();
+void MPU6050_setIntPLLReadyEnabled(bool enabled);
+bool MPU6050_getIntDMPEnabled();
+void MPU6050_setIntDMPEnabled(bool enabled);
+
+// DMP_INT_STATUS
+bool MPU6050_getDMPInt5Status();
+bool MPU6050_getDMPInt4Status();
+bool MPU6050_getDMPInt3Status();
+bool MPU6050_getDMPInt2Status();
+bool MPU6050_getDMPInt1Status();
+bool MPU6050_getDMPInt0Status();
+
+// INT_STATUS register (DMP functions)
+bool MPU6050_getIntPLLReadyStatus();
+bool MPU6050_getIntDMPStatus();
+
+// USER_CTRL register (DMP functions)
+bool MPU6050_getDMPEnabled();
+void MPU6050_setDMPEnabled(bool enabled);
+void MPU6050_resetDMP();
+
+// BANK_SEL register
+void MPU6050_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank);
+
+// MEM_START_ADDR register
+void MPU6050_setMemoryStartAddress(uint8_t address);
+
+// MEM_R_W register
+uint8_t MPU6050_readMemoryByte();
+void MPU6050_writeMemoryByte(uint8_t data);
+void MPU6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address);
+//bool MPU6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem);
+//bool MPU6050_writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify);
+
+//bool MPU6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem);
+//bool MPU6050_writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+// DMP_CFG_1 register
+uint8_t MPU6050_getDMPConfig1();
+void MPU6050_setDMPConfig1(uint8_t config);
+
+// DMP_CFG_2 register
+uint8_t MPU6050_getDMPConfig2();
+void MPU6050_setDMPConfig2(uint8_t config);
+
+#endif /* _MPU6050_H_ */
diff --git a/dsPIC30F/README.md b/dsPIC30F/README.md
new file mode 100644
index 00000000..d63bbbe1
--- /dev/null
+++ b/dsPIC30F/README.md
@@ -0,0 +1,14 @@
+# I2C Device Library for dsPIC30F(under construction)
+
+## I2Cdev
+We use XC16's peripheral libraries (_plib_), read timeout is not implemented.
+
+## Devices
+Currently only MPU6050 is supported without DMP functions. There's an example MPLABX project showing how to read raw data from the MPU.
+
+Adding more functions and devices should be straighforward after reading the source code.
+
+## Licence
+I2Cdev device library code is placed under the MIT license.
+
+_Copyright (c) 2011 Jeff Rowberg. Copyright (c) 2014 Marton Sebok._ Copyright (c) 2017 Daichou.