From 5f14d119084e677aa249350c6423a0920154375d Mon Sep 17 00:00:00 2001 From: Vojtech Bocek Date: Tue, 23 Jan 2024 20:34:04 +0100 Subject: [PATCH] Refactor MPU to use the built-in DMP coprocessor --- fw/rbcx-coprocessor/.vscode/settings.json | 52 +- fw/rbcx-coprocessor/include/Bsp.hpp | 6 + fw/rbcx-coprocessor/include/I2cController.hpp | 13 +- fw/rbcx-coprocessor/include/Mpu6050.hpp | 792 ---- fw/rbcx-coprocessor/include/MpuController.hpp | 794 +--- fw/rbcx-coprocessor/include/MpuDmpCode.hpp | 347 ++ fw/rbcx-coprocessor/include/MpuDriver.hpp | 796 ++++ fw/rbcx-coprocessor/include/utils/Debug.hpp | 2 +- .../include/utils/SemaphoreWrapper.hpp | 40 + .../include/utils/TaskWrapper.hpp | 15 + fw/rbcx-coprocessor/platformio.ini | 2 +- fw/rbcx-coprocessor/src/Bsp.cpp | 8 + fw/rbcx-coprocessor/src/DebugLink.cpp | 2 +- fw/rbcx-coprocessor/src/I2cController.cpp | 105 +- fw/rbcx-coprocessor/src/MpuController.cpp | 3821 ++--------------- fw/rbcx-coprocessor/src/MpuDriver.cpp | 3259 ++++++++++++++ 16 files changed, 4948 insertions(+), 5106 deletions(-) delete mode 100644 fw/rbcx-coprocessor/include/Mpu6050.hpp create mode 100644 fw/rbcx-coprocessor/include/MpuDmpCode.hpp create mode 100644 fw/rbcx-coprocessor/include/MpuDriver.hpp create mode 100644 fw/rbcx-coprocessor/include/utils/SemaphoreWrapper.hpp create mode 100644 fw/rbcx-coprocessor/src/MpuDriver.cpp diff --git a/fw/rbcx-coprocessor/.vscode/settings.json b/fw/rbcx-coprocessor/.vscode/settings.json index a41b9376..0ea76af5 100644 --- a/fw/rbcx-coprocessor/.vscode/settings.json +++ b/fw/rbcx-coprocessor/.vscode/settings.json @@ -3,5 +3,55 @@ "spellright.documentTypes": ["markdown", "latex", "plaintext", "cpp"], "editor.formatOnSave": true, "editor.formatOnPaste": false, - "C_Cpp.default.includePath": ["include/"] + "C_Cpp.default.includePath": [ + "include/" + ], + "files.associations": { + "string_view": "cpp", + "array": "cpp", + "string": "cpp", + "atomic": "cpp", + "*.tcc": "cpp", + "cctype": "cpp", + "chrono": "cpp", + "clocale": "cpp", + "cmath": "cpp", + "condition_variable": "cpp", + "cstdarg": "cpp", + "cstddef": "cpp", + "cstdint": "cpp", + "cstdio": "cpp", + "cstdlib": "cpp", + "ctime": "cpp", + "cwchar": "cpp", + "cwctype": "cpp", + "deque": "cpp", + "unordered_map": "cpp", + "vector": "cpp", + "exception": "cpp", + "algorithm": "cpp", + "functional": "cpp", + "iterator": "cpp", + "memory": "cpp", + "memory_resource": "cpp", + "optional": "cpp", + "ratio": "cpp", + "system_error": "cpp", + "tuple": "cpp", + "type_traits": "cpp", + "utility": "cpp", + "fstream": "cpp", + "initializer_list": "cpp", + "iosfwd": "cpp", + "istream": "cpp", + "limits": "cpp", + "mutex": "cpp", + "new": "cpp", + "ostream": "cpp", + "sstream": "cpp", + "stdexcept": "cpp", + "streambuf": "cpp", + "thread": "cpp", + "typeinfo": "cpp" + } } diff --git a/fw/rbcx-coprocessor/include/Bsp.hpp b/fw/rbcx-coprocessor/include/Bsp.hpp index 9cce700b..c05f072c 100644 --- a/fw/rbcx-coprocessor/include/Bsp.hpp +++ b/fw/rbcx-coprocessor/include/Bsp.hpp @@ -142,6 +142,8 @@ inline const PinDef debugUartTxPin = std::make_pair(GPIOC, GPIO_PIN_10); inline const PinDef debugUartRxPin = std::make_pair(GPIOC, GPIO_PIN_11); inline const PinDef servoUartTxRxPin = std::make_pair(GPIOC, GPIO_PIN_12); +inline const PinDef mpuIntPin = std::make_pair(GPIOD, GPIO_PIN_15); + inline const PinDef i2cSda = std::make_pair(GPIOB, GPIO_PIN_9); inline const PinDef i2cScl = std::make_pair(GPIOB, GPIO_PIN_8); @@ -384,6 +386,10 @@ inline void pinsInit() { HAL_NVIC_SetPriority(EXTI9_5_IRQn, utsIRQPrio, 0); // Ultrasound HAL_NVIC_EnableIRQ(EXTI9_5_IRQn); + // MPU interrupt + pinInit(mpuIntPin, GPIO_MODE_IT_RISING, GPIO_NOPULL, GPIO_SPEED_FREQ_LOW); + HAL_NVIC_SetPriority(EXTI15_10_IRQn, 7, 0); + HAL_NVIC_SetPriority(i2cEvIRQn, i2cIRQnPrio, 0); HAL_NVIC_SetPriority(i2cErIRQn, i2cIRQnPrio, 0); HAL_NVIC_EnableIRQ(i2cEvIRQn); diff --git a/fw/rbcx-coprocessor/include/I2cController.hpp b/fw/rbcx-coprocessor/include/I2cController.hpp index c09c5d20..fd154b77 100644 --- a/fw/rbcx-coprocessor/include/I2cController.hpp +++ b/fw/rbcx-coprocessor/include/I2cController.hpp @@ -46,15 +46,14 @@ THE SOFTWARE. enum I2cEvents : uint32_t { I2C_NONE = 0, - I2C_MPU_TICK = 1, - I2C_MESSAGE = 2, + I2C_MPU_TICK = 1 << 0, + I2C_MESSAGE = 1 << 1, }; -extern TaskHandle_t i2cTaskHandle; -extern EventGroupHandle_t i2cEventGroup; - void i2cDispatch(const CoprocReq_I2cReq& req); void i2cReset(); +void i2cSetEventFlag(I2cEvents flag); +void i2cSetEventFlagFromIsr(I2cEvents flag); #define I2CDEV_DEFAULT_READ_TIMEOUT 10 @@ -103,6 +102,6 @@ uint16_t I2Cdev_writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint16_t I2Cdev_writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); uint16_t I2Cdev_writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); uint16_t I2Cdev_writeBytes( - uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data); + uint8_t devAddr, uint8_t regAddr, uint8_t length, const uint8_t* data); uint16_t I2Cdev_writeWords( - uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data); + uint8_t devAddr, uint8_t regAddr, uint8_t length, const uint16_t* data); diff --git a/fw/rbcx-coprocessor/include/Mpu6050.hpp b/fw/rbcx-coprocessor/include/Mpu6050.hpp deleted file mode 100644 index 2bf96743..00000000 --- a/fw/rbcx-coprocessor/include/Mpu6050.hpp +++ /dev/null @@ -1,792 +0,0 @@ -// 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 -// 2017-03-11 - tested basic functions on STM32 - -// 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 "I2cController.hpp" -#include - -// clang-format off - -#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_init(); - -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/fw/rbcx-coprocessor/include/MpuController.hpp b/fw/rbcx-coprocessor/include/MpuController.hpp index 3f702e47..95c66486 100644 --- a/fw/rbcx-coprocessor/include/MpuController.hpp +++ b/fw/rbcx-coprocessor/include/MpuController.hpp @@ -1,419 +1,6 @@ -// I2Cdev library collection - mpu 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 -// 2017-03-11 - tested basic functions on STM32 +#pragma once -// 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 _mpu_H_ -#define _mpu_H_ - -#include "I2cController.hpp" #include "rbcx.pb.h" -#include - -#if ((defined mpu_INCLUDE_DMP_MOTIONAPPS20) \ - || (defined mpu_INCLUDE_DMP_MOTIONAPPS41)) -#error DMP is not supported yet -#endif - -#define mpu_ADDRESS_AD0_LOW \ - 0x68 // address pin low (GND), default for InvenSense evaluation board -#define mpu_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC) -#define mpu_DEFAULT_ADDRESS mpu_ADDRESS_AD0_LOW - -#define mpu_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD -#define mpu_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD -#define mpu_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD -#define mpu_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN -#define mpu_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN -#define mpu_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN -#define mpu_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS -#define mpu_RA_XA_OFFS_L_TC 0x07 -#define mpu_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS -#define mpu_RA_YA_OFFS_L_TC 0x09 -#define mpu_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS -#define mpu_RA_ZA_OFFS_L_TC 0x0B -#define mpu_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR -#define mpu_RA_XG_OFFS_USRL 0x14 -#define mpu_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR -#define mpu_RA_YG_OFFS_USRL 0x16 -#define mpu_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR -#define mpu_RA_ZG_OFFS_USRL 0x18 -#define mpu_RA_SMPLRT_DIV 0x19 -#define mpu_RA_CONFIG 0x1A -#define mpu_RA_GYRO_CONFIG 0x1B -#define mpu_RA_ACCEL_CONFIG 0x1C -#define mpu_RA_FF_THR 0x1D -#define mpu_RA_FF_DUR 0x1E -#define mpu_RA_MOT_THR 0x1F -#define mpu_RA_MOT_DUR 0x20 -#define mpu_RA_ZRMOT_THR 0x21 -#define mpu_RA_ZRMOT_DUR 0x22 -#define mpu_RA_FIFO_EN 0x23 -#define mpu_RA_I2C_MST_CTRL 0x24 -#define mpu_RA_I2C_SLV0_ADDR 0x25 -#define mpu_RA_I2C_SLV0_REG 0x26 -#define mpu_RA_I2C_SLV0_CTRL 0x27 -#define mpu_RA_I2C_SLV1_ADDR 0x28 -#define mpu_RA_I2C_SLV1_REG 0x29 -#define mpu_RA_I2C_SLV1_CTRL 0x2A -#define mpu_RA_I2C_SLV2_ADDR 0x2B -#define mpu_RA_I2C_SLV2_REG 0x2C -#define mpu_RA_I2C_SLV2_CTRL 0x2D -#define mpu_RA_I2C_SLV3_ADDR 0x2E -#define mpu_RA_I2C_SLV3_REG 0x2F -#define mpu_RA_I2C_SLV3_CTRL 0x30 -#define mpu_RA_I2C_SLV4_ADDR 0x31 -#define mpu_RA_I2C_SLV4_REG 0x32 -#define mpu_RA_I2C_SLV4_DO 0x33 -#define mpu_RA_I2C_SLV4_CTRL 0x34 -#define mpu_RA_I2C_SLV4_DI 0x35 -#define mpu_RA_I2C_MST_STATUS 0x36 -#define mpu_RA_INT_PIN_CFG 0x37 -#define mpu_RA_INT_ENABLE 0x38 -#define mpu_RA_DMP_INT_STATUS 0x39 -#define mpu_RA_INT_STATUS 0x3A -#define mpu_RA_ACCEL_XOUT_H 0x3B -#define mpu_RA_ACCEL_XOUT_L 0x3C -#define mpu_RA_ACCEL_YOUT_H 0x3D -#define mpu_RA_ACCEL_YOUT_L 0x3E -#define mpu_RA_ACCEL_ZOUT_H 0x3F -#define mpu_RA_ACCEL_ZOUT_L 0x40 -#define mpu_RA_TEMP_OUT_H 0x41 -#define mpu_RA_TEMP_OUT_L 0x42 -#define mpu_RA_GYRO_XOUT_H 0x43 -#define mpu_RA_GYRO_XOUT_L 0x44 -#define mpu_RA_GYRO_YOUT_H 0x45 -#define mpu_RA_GYRO_YOUT_L 0x46 -#define mpu_RA_GYRO_ZOUT_H 0x47 -#define mpu_RA_GYRO_ZOUT_L 0x48 -#define mpu_RA_EXT_SENS_DATA_00 0x49 -#define mpu_RA_EXT_SENS_DATA_01 0x4A -#define mpu_RA_EXT_SENS_DATA_02 0x4B -#define mpu_RA_EXT_SENS_DATA_03 0x4C -#define mpu_RA_EXT_SENS_DATA_04 0x4D -#define mpu_RA_EXT_SENS_DATA_05 0x4E -#define mpu_RA_EXT_SENS_DATA_06 0x4F -#define mpu_RA_EXT_SENS_DATA_07 0x50 -#define mpu_RA_EXT_SENS_DATA_08 0x51 -#define mpu_RA_EXT_SENS_DATA_09 0x52 -#define mpu_RA_EXT_SENS_DATA_10 0x53 -#define mpu_RA_EXT_SENS_DATA_11 0x54 -#define mpu_RA_EXT_SENS_DATA_12 0x55 -#define mpu_RA_EXT_SENS_DATA_13 0x56 -#define mpu_RA_EXT_SENS_DATA_14 0x57 -#define mpu_RA_EXT_SENS_DATA_15 0x58 -#define mpu_RA_EXT_SENS_DATA_16 0x59 -#define mpu_RA_EXT_SENS_DATA_17 0x5A -#define mpu_RA_EXT_SENS_DATA_18 0x5B -#define mpu_RA_EXT_SENS_DATA_19 0x5C -#define mpu_RA_EXT_SENS_DATA_20 0x5D -#define mpu_RA_EXT_SENS_DATA_21 0x5E -#define mpu_RA_EXT_SENS_DATA_22 0x5F -#define mpu_RA_EXT_SENS_DATA_23 0x60 -#define mpu_RA_MOT_DETECT_STATUS 0x61 -#define mpu_RA_I2C_SLV0_DO 0x63 -#define mpu_RA_I2C_SLV1_DO 0x64 -#define mpu_RA_I2C_SLV2_DO 0x65 -#define mpu_RA_I2C_SLV3_DO 0x66 -#define mpu_RA_I2C_MST_DELAY_CTRL 0x67 -#define mpu_RA_SIGNAL_PATH_RESET 0x68 -#define mpu_RA_MOT_DETECT_CTRL 0x69 -#define mpu_RA_USER_CTRL 0x6A -#define mpu_RA_PWR_MGMT_1 0x6B -#define mpu_RA_PWR_MGMT_2 0x6C -#define mpu_RA_BANK_SEL 0x6D -#define mpu_RA_MEM_START_ADDR 0x6E -#define mpu_RA_MEM_R_W 0x6F -#define mpu_RA_DMP_CFG_1 0x70 -#define mpu_RA_DMP_CFG_2 0x71 -#define mpu_RA_FIFO_COUNTH 0x72 -#define mpu_RA_FIFO_COUNTL 0x73 -#define mpu_RA_FIFO_R_W 0x74 -#define mpu_RA_WHO_AM_I 0x75 - -#define mpu_TC_PWR_MODE_BIT 7 -#define mpu_TC_OFFSET_BIT 6 -#define mpu_TC_OFFSET_LENGTH 6 -#define mpu_TC_OTP_BNK_VLD_BIT 0 - -#define mpu_VDDIO_LEVEL_VLOGIC 0 -#define mpu_VDDIO_LEVEL_VDD 1 - -#define mpu_CFG_EXT_SYNC_SET_BIT 5 -#define mpu_CFG_EXT_SYNC_SET_LENGTH 3 -#define mpu_CFG_DLPF_CFG_BIT 2 -#define mpu_CFG_DLPF_CFG_LENGTH 3 - -#define mpu_EXT_SYNC_DISABLED 0x0 -#define mpu_EXT_SYNC_TEMP_OUT_L 0x1 -#define mpu_EXT_SYNC_GYRO_XOUT_L 0x2 -#define mpu_EXT_SYNC_GYRO_YOUT_L 0x3 -#define mpu_EXT_SYNC_GYRO_ZOUT_L 0x4 -#define mpu_EXT_SYNC_ACCEL_XOUT_L 0x5 -#define mpu_EXT_SYNC_ACCEL_YOUT_L 0x6 -#define mpu_EXT_SYNC_ACCEL_ZOUT_L 0x7 - -#define mpu_DLPF_BW_256 0x00 -#define mpu_DLPF_BW_188 0x01 -#define mpu_DLPF_BW_98 0x02 -#define mpu_DLPF_BW_42 0x03 -#define mpu_DLPF_BW_20 0x04 -#define mpu_DLPF_BW_10 0x05 -#define mpu_DLPF_BW_5 0x06 - -#define mpu_GCONFIG_FS_SEL_BIT 4 -#define mpu_GCONFIG_FS_SEL_LENGTH 2 - -#define mpu_GYRO_FS_250 0x00 -#define mpu_GYRO_FS_500 0x01 -#define mpu_GYRO_FS_1000 0x02 -#define mpu_GYRO_FS_2000 0x03 - -#define mpu_ACONFIG_XA_ST_BIT 7 -#define mpu_ACONFIG_YA_ST_BIT 6 -#define mpu_ACONFIG_ZA_ST_BIT 5 -#define mpu_ACONFIG_AFS_SEL_BIT 4 -#define mpu_ACONFIG_AFS_SEL_LENGTH 2 -#define mpu_ACONFIG_ACCEL_HPF_BIT 2 -#define mpu_ACONFIG_ACCEL_HPF_LENGTH 3 - -#define mpu_ACCEL_FS_2 0x00 -#define mpu_ACCEL_FS_4 0x01 -#define mpu_ACCEL_FS_8 0x02 -#define mpu_ACCEL_FS_16 0x03 - -#define mpu_DHPF_RESET 0x00 -#define mpu_DHPF_5 0x01 -#define mpu_DHPF_2P5 0x02 -#define mpu_DHPF_1P25 0x03 -#define mpu_DHPF_0P63 0x04 -#define mpu_DHPF_HOLD 0x07 - -#define mpu_TEMP_FIFO_EN_BIT 7 -#define mpu_XG_FIFO_EN_BIT 6 -#define mpu_YG_FIFO_EN_BIT 5 -#define mpu_ZG_FIFO_EN_BIT 4 -#define mpu_ACCEL_FIFO_EN_BIT 3 -#define mpu_SLV2_FIFO_EN_BIT 2 -#define mpu_SLV1_FIFO_EN_BIT 1 -#define mpu_SLV0_FIFO_EN_BIT 0 - -#define mpu_MULT_MST_EN_BIT 7 -#define mpu_WAIT_FOR_ES_BIT 6 -#define mpu_SLV_3_FIFO_EN_BIT 5 -#define mpu_I2C_MST_P_NSR_BIT 4 -#define mpu_I2C_MST_CLK_BIT 3 -#define mpu_I2C_MST_CLK_LENGTH 4 - -#define mpu_CLOCK_DIV_348 0x0 -#define mpu_CLOCK_DIV_333 0x1 -#define mpu_CLOCK_DIV_320 0x2 -#define mpu_CLOCK_DIV_308 0x3 -#define mpu_CLOCK_DIV_296 0x4 -#define mpu_CLOCK_DIV_286 0x5 -#define mpu_CLOCK_DIV_276 0x6 -#define mpu_CLOCK_DIV_267 0x7 -#define mpu_CLOCK_DIV_258 0x8 -#define mpu_CLOCK_DIV_500 0x9 -#define mpu_CLOCK_DIV_471 0xA -#define mpu_CLOCK_DIV_444 0xB -#define mpu_CLOCK_DIV_421 0xC -#define mpu_CLOCK_DIV_400 0xD -#define mpu_CLOCK_DIV_381 0xE -#define mpu_CLOCK_DIV_364 0xF - -#define mpu_I2C_SLV_RW_BIT 7 -#define mpu_I2C_SLV_ADDR_BIT 6 -#define mpu_I2C_SLV_ADDR_LENGTH 7 -#define mpu_I2C_SLV_EN_BIT 7 -#define mpu_I2C_SLV_BYTE_SW_BIT 6 -#define mpu_I2C_SLV_REG_DIS_BIT 5 -#define mpu_I2C_SLV_GRP_BIT 4 -#define mpu_I2C_SLV_LEN_BIT 3 -#define mpu_I2C_SLV_LEN_LENGTH 4 - -#define mpu_I2C_SLV4_RW_BIT 7 -#define mpu_I2C_SLV4_ADDR_BIT 6 -#define mpu_I2C_SLV4_ADDR_LENGTH 7 -#define mpu_I2C_SLV4_EN_BIT 7 -#define mpu_I2C_SLV4_INT_EN_BIT 6 -#define mpu_I2C_SLV4_REG_DIS_BIT 5 -#define mpu_I2C_SLV4_MST_DLY_BIT 4 -#define mpu_I2C_SLV4_MST_DLY_LENGTH 5 - -#define mpu_MST_PASS_THROUGH_BIT 7 -#define mpu_MST_I2C_SLV4_DONE_BIT 6 -#define mpu_MST_I2C_LOST_ARB_BIT 5 -#define mpu_MST_I2C_SLV4_NACK_BIT 4 -#define mpu_MST_I2C_SLV3_NACK_BIT 3 -#define mpu_MST_I2C_SLV2_NACK_BIT 2 -#define mpu_MST_I2C_SLV1_NACK_BIT 1 -#define mpu_MST_I2C_SLV0_NACK_BIT 0 - -#define mpu_INTCFG_INT_LEVEL_BIT 7 -#define mpu_INTCFG_INT_OPEN_BIT 6 -#define mpu_INTCFG_LATCH_INT_EN_BIT 5 -#define mpu_INTCFG_INT_RD_CLEAR_BIT 4 -#define mpu_INTCFG_FSYNC_INT_LEVEL_BIT 3 -#define mpu_INTCFG_FSYNC_INT_EN_BIT 2 -#define mpu_INTCFG_I2C_BYPASS_EN_BIT 1 -#define mpu_INTCFG_CLKOUT_EN_BIT 0 - -#define mpu_INTMODE_ACTIVEHIGH 0x00 -#define mpu_INTMODE_ACTIVELOW 0x01 - -#define mpu_INTDRV_PUSHPULL 0x00 -#define mpu_INTDRV_OPENDRAIN 0x01 - -#define mpu_INTLATCH_50USPULSE 0x00 -#define mpu_INTLATCH_WAITCLEAR 0x01 - -#define mpu_INTCLEAR_STATUSREAD 0x00 -#define mpu_INTCLEAR_ANYREAD 0x01 - -#define mpu_INTERRUPT_FF_BIT 7 -#define mpu_INTERRUPT_MOT_BIT 6 -#define mpu_INTERRUPT_ZMOT_BIT 5 -#define mpu_INTERRUPT_FIFO_OFLOW_BIT 4 -#define mpu_INTERRUPT_I2C_MST_INT_BIT 3 -#define mpu_INTERRUPT_PLL_RDY_INT_BIT 2 -#define mpu_INTERRUPT_DMP_INT_BIT 1 -#define mpu_INTERRUPT_DATA_RDY_BIT 0 - -// TODO: figure out what these actually do -// UMPL source code is not very obivous -#define mpu_DMPINT_5_BIT 5 -#define mpu_DMPINT_4_BIT 4 -#define mpu_DMPINT_3_BIT 3 -#define mpu_DMPINT_2_BIT 2 -#define mpu_DMPINT_1_BIT 1 -#define mpu_DMPINT_0_BIT 0 - -#define mpu_MOTION_MOT_XNEG_BIT 7 -#define mpu_MOTION_MOT_XPOS_BIT 6 -#define mpu_MOTION_MOT_YNEG_BIT 5 -#define mpu_MOTION_MOT_YPOS_BIT 4 -#define mpu_MOTION_MOT_ZNEG_BIT 3 -#define mpu_MOTION_MOT_ZPOS_BIT 2 -#define mpu_MOTION_MOT_ZRMOT_BIT 0 - -#define mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT 7 -#define mpu_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4 -#define mpu_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3 -#define mpu_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2 -#define mpu_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1 -#define mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0 - -#define mpu_PATHRESET_GYRO_RESET_BIT 2 -#define mpu_PATHRESET_ACCEL_RESET_BIT 1 -#define mpu_PATHRESET_TEMP_RESET_BIT 0 - -#define mpu_DETECT_ACCEL_ON_DELAY_BIT 5 -#define mpu_DETECT_ACCEL_ON_DELAY_LENGTH 2 -#define mpu_DETECT_FF_COUNT_BIT 3 -#define mpu_DETECT_FF_COUNT_LENGTH 2 -#define mpu_DETECT_MOT_COUNT_BIT 1 -#define mpu_DETECT_MOT_COUNT_LENGTH 2 - -#define mpu_DETECT_DECREMENT_RESET 0x0 -#define mpu_DETECT_DECREMENT_1 0x1 -#define mpu_DETECT_DECREMENT_2 0x2 -#define mpu_DETECT_DECREMENT_4 0x3 - -#define mpu_USERCTRL_DMP_EN_BIT 7 -#define mpu_USERCTRL_FIFO_EN_BIT 6 -#define mpu_USERCTRL_I2C_MST_EN_BIT 5 -#define mpu_USERCTRL_I2C_IF_DIS_BIT 4 -#define mpu_USERCTRL_DMP_RESET_BIT 3 -#define mpu_USERCTRL_FIFO_RESET_BIT 2 -#define mpu_USERCTRL_I2C_MST_RESET_BIT 1 -#define mpu_USERCTRL_SIG_COND_RESET_BIT 0 - -#define mpu_PWR1_DEVICE_RESET_BIT 7 -#define mpu_PWR1_SLEEP_BIT 6 -#define mpu_PWR1_CYCLE_BIT 5 -#define mpu_PWR1_TEMP_DIS_BIT 3 -#define mpu_PWR1_CLKSEL_BIT 2 -#define mpu_PWR1_CLKSEL_LENGTH 3 - -#define mpu_CLOCK_INTERNAL 0x00 -#define mpu_CLOCK_PLL_XGYRO 0x01 -#define mpu_CLOCK_PLL_YGYRO 0x02 -#define mpu_CLOCK_PLL_ZGYRO 0x03 -#define mpu_CLOCK_PLL_EXT32K 0x04 -#define mpu_CLOCK_PLL_EXT19M 0x05 -#define mpu_CLOCK_KEEP_RESET 0x07 - -#define mpu_PWR2_LP_WAKE_CTRL_BIT 7 -#define mpu_PWR2_LP_WAKE_CTRL_LENGTH 2 -#define mpu_PWR2_STBY_XA_BIT 5 -#define mpu_PWR2_STBY_YA_BIT 4 -#define mpu_PWR2_STBY_ZA_BIT 3 -#define mpu_PWR2_STBY_XG_BIT 2 -#define mpu_PWR2_STBY_YG_BIT 1 -#define mpu_PWR2_STBY_ZG_BIT 0 - -#define mpu_WAKE_FREQ_1P25 0x0 -#define mpu_WAKE_FREQ_2P5 0x1 -#define mpu_WAKE_FREQ_5 0x2 -#define mpu_WAKE_FREQ_10 0x3 - -#define mpu_BANKSEL_PRFTCH_EN_BIT 6 -#define mpu_BANKSEL_CFG_USER_BANK_BIT 5 -#define mpu_BANKSEL_MEM_SEL_BIT 4 -#define mpu_BANKSEL_MEM_SEL_LENGTH 5 - -#define mpu_WHO_AM_I_BIT 6 -#define mpu_WHO_AM_I_LENGTH 6 - -#define mpu_DMP_MEMORY_BANKS 8 -#define mpu_DMP_MEMORY_BANK_SIZE 256 -#define mpu_DMP_MEMORY_CHUNK_SIZE 16 - -// note: DMP code memory blocks defined at end of header file - -// #define COMPRESS_COEF 4 - -typedef struct mpu_t { - uint8_t devAddr; - uint8_t buffer[14]; -} mpu_t; void mpuDispatch(const CoprocReq_MpuReq& request); void mpuTick(); @@ -421,381 +8,4 @@ void mpuTick(); void mpuCreate(); void mpuInitialize(); void mpuReset(); -bool mpu_testConnection(); - -// AUX_VDDIO register -uint8_t mpu_getAuxVDDIOLevel(); -void mpu_setAuxVDDIOLevel(uint8_t level); - -// SMPLRT_DIV register -uint8_t mpu_getRate(); -void mpu_setRate(uint8_t rate); - -// CONFIG register -uint8_t mpu_getExternalFrameSync(); -void mpu_setExternalFrameSync(uint8_t sync); -uint8_t mpu_getDLPFMode(); -void mpu_setDLPFMode(uint8_t bandwidth); - -// GYRO_CONFIG register -uint8_t mpu_getFullScaleGyroRange(); -void mpu_setFullScaleGyroRange(uint8_t range); - -// ACCEL_CONFIG register -bool mpu_getAccelXSelfTest(); -void mpu_setAccelXSelfTest(bool enabled); -bool mpu_getAccelYSelfTest(); -void mpu_setAccelYSelfTest(bool enabled); -bool mpu_getAccelZSelfTest(); -void mpu_setAccelZSelfTest(bool enabled); -uint8_t mpu_getFullScaleAccelRange(); -void mpu_setFullScaleAccelRange(uint8_t range); -uint8_t mpu_getDHPFMode(); -void mpu_setDHPFMode(uint8_t mode); - -// FF_THR register -uint8_t mpu_getFreefallDetectionThreshold(); -void mpu_setFreefallDetectionThreshold(uint8_t threshold); - -// FF_DUR register -uint8_t mpu_getFreefallDetectionDuration(); -void mpu_setFreefallDetectionDuration(uint8_t duration); - -// MOT_THR register -uint8_t mpu_getMotionDetectionThreshold(); -void mpu_setMotionDetectionThreshold(uint8_t threshold); - -// MOT_DUR register -uint8_t mpu_getMotionDetectionDuration(); -void mpu_setMotionDetectionDuration(uint8_t duration); - -// ZRMOT_THR register -uint8_t mpu_getZeroMotionDetectionThreshold(); -void mpu_setZeroMotionDetectionThreshold(uint8_t threshold); - -// ZRMOT_DUR register -uint8_t mpu_getZeroMotionDetectionDuration(); -void mpu_setZeroMotionDetectionDuration(uint8_t duration); - -// FIFO_EN register -bool mpu_getTempFIFOEnabled(); -void mpu_setTempFIFOEnabled(bool enabled); -bool mpu_getXGyroFIFOEnabled(); -void mpu_setXGyroFIFOEnabled(bool enabled); -bool mpu_getYGyroFIFOEnabled(); -void mpu_setYGyroFIFOEnabled(bool enabled); -bool mpu_getZGyroFIFOEnabled(); -void mpu_setZGyroFIFOEnabled(bool enabled); -bool mpu_getAccelFIFOEnabled(); -void mpu_setAccelFIFOEnabled(bool enabled); -bool mpu_getSlave2FIFOEnabled(); -void mpu_setSlave2FIFOEnabled(bool enabled); -bool mpu_getSlave1FIFOEnabled(); -void mpu_setSlave1FIFOEnabled(bool enabled); -bool mpu_getSlave0FIFOEnabled(); -void mpu_setSlave0FIFOEnabled(bool enabled); - -// I2C_MST_CTRL register -bool mpu_getMultiMasterEnabled(); -void mpu_setMultiMasterEnabled(bool enabled); -bool mpu_getWaitForExternalSensorEnabled(); -void mpu_setWaitForExternalSensorEnabled(bool enabled); -bool mpu_getSlave3FIFOEnabled(); -void mpu_setSlave3FIFOEnabled(bool enabled); -bool mpu_getSlaveReadWriteTransitionEnabled(); -void mpu_setSlaveReadWriteTransitionEnabled(bool enabled); -uint8_t mpu_getMasterClockSpeed(); -void mpu_setMasterClockSpeed(uint8_t speed); - -// I2C_SLV* registers (Slave 0-3) -uint8_t mpu_getSlaveAddress(uint8_t num); -void mpu_setSlaveAddress(uint8_t num, uint8_t address); -uint8_t mpu_getSlaveRegister(uint8_t num); -void mpu_setSlaveRegister(uint8_t num, uint8_t reg); -bool mpu_getSlaveEnabled(uint8_t num); -void mpu_setSlaveEnabled(uint8_t num, bool enabled); -bool mpu_getSlaveWordByteSwap(uint8_t num); -void mpu_setSlaveWordByteSwap(uint8_t num, bool enabled); -bool mpu_getSlaveWriteMode(uint8_t num); -void mpu_setSlaveWriteMode(uint8_t num, bool mode); -bool mpu_getSlaveWordGroupOffset(uint8_t num); -void mpu_setSlaveWordGroupOffset(uint8_t num, bool enabled); -uint8_t mpu_getSlaveDataLength(uint8_t num); -void mpu_setSlaveDataLength(uint8_t num, uint8_t length); - -// I2C_SLV* registers (Slave 4) -uint8_t mpu_getSlave4Address(); -void mpu_setSlave4Address(uint8_t address); -uint8_t mpu_getSlave4Register(); -void mpu_setSlave4Register(uint8_t reg); -void mpu_setSlave4OutputByte(uint8_t data); -bool mpu_getSlave4Enabled(); -void mpu_setSlave4Enabled(bool enabled); -bool mpu_getSlave4InterruptEnabled(); -void mpu_setSlave4InterruptEnabled(bool enabled); -bool mpu_getSlave4WriteMode(); -void mpu_setSlave4WriteMode(bool mode); -uint8_t mpu_getSlave4MasterDelay(); -void mpu_setSlave4MasterDelay(uint8_t delay); -uint8_t mpu_getSlate4InputByte(); - -// I2C_MST_STATUS register -bool mpu_getPassthroughStatus(); -bool mpu_getSlave4IsDone(); -bool mpu_getLostArbitration(); -bool mpu_getSlave4Nack(); -bool mpu_getSlave3Nack(); -bool mpu_getSlave2Nack(); -bool mpu_getSlave1Nack(); -bool mpu_getSlave0Nack(); - -// INT_PIN_CFG register -bool mpu_getInterruptMode(); -void mpu_setInterruptMode(bool mode); -bool mpu_getInterruptDrive(); -void mpu_setInterruptDrive(bool drive); -bool mpu_getInterruptLatch(); -void mpu_setInterruptLatch(bool latch); -bool mpu_getInterruptLatchClear(); -void mpu_setInterruptLatchClear(bool clear); -bool mpu_getFSyncInterruptLevel(); -void mpu_setFSyncInterruptLevel(bool level); -bool mpu_getFSyncInterruptEnabled(); -void mpu_setFSyncInterruptEnabled(bool enabled); -bool mpu_getI2CBypassEnabled(); -void mpu_setI2CBypassEnabled(bool enabled); -bool mpu_getClockOutputEnabled(); -void mpu_setClockOutputEnabled(bool enabled); - -// INT_ENABLE register -uint8_t mpu_getIntEnabled(); -void mpu_setIntEnabled(uint8_t enabled); -bool mpu_getIntFreefallEnabled(); -void mpu_setIntFreefallEnabled(bool enabled); -bool mpu_getIntMotionEnabled(); -void mpu_setIntMotionEnabled(bool enabled); -bool mpu_getIntZeroMotionEnabled(); -void mpu_setIntZeroMotionEnabled(bool enabled); -bool mpu_getIntFIFOBufferOverflowEnabled(); -void mpu_setIntFIFOBufferOverflowEnabled(bool enabled); -bool mpu_getIntI2CMasterEnabled(); -void mpu_setIntI2CMasterEnabled(bool enabled); -bool mpu_getIntDataReadyEnabled(); -void mpu_setIntDataReadyEnabled(bool enabled); - -// INT_STATUS register -uint8_t mpu_getIntStatus(); -bool mpu_getIntFreefallStatus(); -bool mpu_getIntMotionStatus(); -bool mpu_getIntZeroMotionStatus(); -bool mpu_getIntFIFOBufferOverflowStatus(); -bool mpu_getIntI2CMasterStatus(); -bool mpu_getIntDataReadyStatus(); - -// ACCEL_*OUT_* registers -void mpu_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 mpu_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, - int16_t* gy, int16_t* gz); -void mpu_getAcceleration(int16_t* x, int16_t* y, int16_t* z); -// void mpu_getAcceleration(int32_t* x, int32_t* y, int32_t* z); -int16_t mpu_getAccelerationX(); -int16_t mpu_getAccelerationY(); -int16_t mpu_getAccelerationZ(); - -// TEMP_OUT_* registers -int16_t mpu_getTemperature(); - -// GYRO_*OUT_* registers -void mpu_getRotation(int16_t* x, int16_t* y, int16_t* z); -// void mpu_getRotation(int32_t* x, int32_t* y, int32_t* z); -int16_t mpu_getRotationX(); -int16_t mpu_getRotationY(); -int16_t mpu_getRotationZ(); - -// EXT_SENS_DATA_* registers -uint8_t mpu_getExternalSensorByte(int position); -uint16_t mpu_getExternalSensorWord(int position); -uint32_t getExternalSensorDWord(int position); - -// MOT_DETECT_STATUS register -bool mpu_getXNegMotionDetected(); -bool mpu_getXPosMotionDetected(); -bool mpu_getYNegMotionDetected(); -bool mpu_getYPosMotionDetected(); -bool mpu_getZNegMotionDetected(); -bool mpu_getZPosMotionDetected(); -bool mpu_getZeroMotionDetected(); - -// I2C_SLV*_DO register -void mpu_setSlaveOutputByte(uint8_t num, uint8_t data); - -// I2C_MST_DELAY_CTRL register -bool mpu_getExternalShadowDelayEnabled(); -void mpu_setExternalShadowDelayEnabled(bool enabled); -bool mpu_getSlaveDelayEnabled(uint8_t num); -void mpu_setSlaveDelayEnabled(uint8_t num, bool enabled); - -// SIGNAL_PATH_RESET register -void mpu_resetGyroscopePath(); -void mpu_resetAccelerometerPath(); -void mpu_resetTemperaturePath(); - -// MOT_DETECT_CTRL register -uint8_t mpu_getAccelerometerPowerOnDelay(); -void mpu_setAccelerometerPowerOnDelay(uint8_t delay); -uint8_t mpu_getFreefallDetectionCounterDecrement(); -void mpu_setFreefallDetectionCounterDecrement(uint8_t decrement); -uint8_t mpu_getMotionDetectionCounterDecrement(); -void mpu_setMotionDetectionCounterDecrement(uint8_t decrement); - -// USER_CTRL register -bool mpu_getFIFOEnabled(); -void mpu_setFIFOEnabled(bool enabled); -bool mpu_getI2CMasterModeEnabled(); -void mpu_setI2CMasterModeEnabled(bool enabled); -void mpu_switchSPIEnabled(bool enabled); -void mpu_resetFIFO(); -void mpu_resetI2CMaster(); -void mpu_resetSensors(); - -// PWR_MGMT_1 register -void mpu_reset(); -bool mpu_getSleepEnabled(); -void mpu_setSleepEnabled(bool enabled); -bool mpu_getWakeCycleEnabled(); -void mpu_setWakeCycleEnabled(bool enabled); -bool mpu_getTempSensorEnabled(); -void mpu_setTempSensorEnabled(bool enabled); -uint8_t mpu_getClockSource(); -void mpu_setClockSource(uint8_t source); - -// PWR_MGMT_2 register -uint8_t mpu_getWakeFrequency(); -void mpu_setWakeFrequency(uint8_t frequency); -bool mpu_getStandbyXAccelEnabled(); -void mpu_setStandbyXAccelEnabled(bool enabled); -bool mpu_getStandbyYAccelEnabled(); -void mpu_setStandbyYAccelEnabled(bool enabled); -bool mpu_getStandbyZAccelEnabled(); -void mpu_setStandbyZAccelEnabled(bool enabled); -bool mpu_getStandbyXGyroEnabled(); -void mpu_setStandbyXGyroEnabled(bool enabled); -bool mpu_getStandbyYGyroEnabled(); -void mpu_setStandbyYGyroEnabled(bool enabled); -bool mpu_getStandbyZGyroEnabled(); -void mpu_setStandbyZGyroEnabled(bool enabled); - -// FIFO_COUNT_* registers -uint16_t mpu_getFIFOCount(); - -// FIFO_R_W register -uint8_t mpu_getFIFOByte(); -void mpu_setFIFOByte(uint8_t data); -void mpu_getFIFOBytes(uint8_t* data, uint8_t length); - -// WHO_AM_I register -uint8_t mpu_getDeviceID(); -void mpu_setDeviceID(uint8_t id); - -// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== - -// XG_OFFS_TC register -uint8_t mpu_getOTPBankValid(); -void mpu_setOTPBankValid(bool enabled); -int8_t getXGyroOffsetTC(); -void mpu_setXGyroOffsetTC(int8_t offset); - -// YG_OFFS_TC register -int8_t getYGyroOffsetTC(); -void mpu_setYGyroOffsetTC(int8_t offset); - -// ZG_OFFS_TC register -int8_t getZGyroOffsetTC(); -void mpu_setZGyroOffsetTC(int8_t offset); - -// X_FINE_GAIN register -int8_t getXFineGain(); -void mpu_setXFineGain(int8_t gain); - -// Y_FINE_GAIN register -int8_t getYFineGain(); -void mpu_setYFineGain(int8_t gain); - -// Z_FINE_GAIN register -int8_t getZFineGain(); -void mpu_setZFineGain(int8_t gain); - -// XA_OFFS_* registers -int16_t mpu_getXAccelOffset(); -void mpu_setXAccelOffset(int16_t offset); - -// YA_OFFS_* register -int16_t mpu_getYAccelOffset(); -void mpu_setYAccelOffset(int16_t offset); - -// ZA_OFFS_* register -int16_t mpu_getZAccelOffset(); -void mpu_setZAccelOffset(int16_t offset); - -// XG_OFFS_USR* registers -int16_t mpu_getXGyroOffset(); -void mpu_setXGyroOffset(int16_t offset); - -// YG_OFFS_USR* register -int16_t mpu_getYGyroOffset(); -void mpu_setYGyroOffset(int16_t offset); - -// ZG_OFFS_USR* register -int16_t mpu_getZGyroOffset(); -void mpu_setZGyroOffset(int16_t offset); - -// INT_ENABLE register (DMP functions) -bool mpu_getIntPLLReadyEnabled(); -void mpu_setIntPLLReadyEnabled(bool enabled); -bool mpu_getIntDMPEnabled(); -void mpu_setIntDMPEnabled(bool enabled); - -// DMP_INT_STATUS -bool mpu_getDMPInt5Status(); -bool mpu_getDMPInt4Status(); -bool mpu_getDMPInt3Status(); -bool mpu_getDMPInt2Status(); -bool mpu_getDMPInt1Status(); -bool mpu_getDMPInt0Status(); - -// INT_STATUS register (DMP functions) -bool mpu_getIntPLLReadyStatus(); -bool mpu_getIntDMPStatus(); - -// USER_CTRL register (DMP functions) -bool mpu_getDMPEnabled(); -void mpu_setDMPEnabled(bool enabled); -void mpu_resetDMP(); - -// BANK_SEL register -void mpu_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank); - -// MEM_START_ADDR register -void mpu_setMemoryStartAddress(uint8_t address); - -// MEM_R_W register -uint8_t mpu_readMemoryByte(); -void mpu_writeMemoryByte(uint8_t data); -void mpu_readMemoryBlock( - uint8_t* data, uint16_t dataSize, uint8_t bank, uint8_t address); -//bool mpu_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem); -//bool mpu_writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify); - -//bool mpu_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem); -//bool mpu_writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize); - -// DMP_CFG_1 register -uint8_t mpu_getDMPConfig1(); -void mpu_setDMPConfig1(uint8_t config); - -// DMP_CFG_2 register -uint8_t mpu_getDMPConfig2(); -void mpu_setDMPConfig2(uint8_t config); - -#endif /* _mpu_H_ */ +void mpuOnIntTriggered(); diff --git a/fw/rbcx-coprocessor/include/MpuDmpCode.hpp b/fw/rbcx-coprocessor/include/MpuDmpCode.hpp new file mode 100644 index 00000000..9817ce3d --- /dev/null +++ b/fw/rbcx-coprocessor/include/MpuDmpCode.hpp @@ -0,0 +1,347 @@ +// clang-format off + +#pragma once + +#include + + +// https://github.com/ElectronicCats/mpu6050/blob/df034d8a2d1eb862c189ce27d0abfd93e6649d57/src/MPU6050_6Axis_MotionApps612.cpp#L134 +static const uint8_t dmpCode612[] = { +/* bank # 0 */ +0x00, 0xF8, 0xF6, 0x2A, 0x3F, 0x68, 0xF5, 0x7A, 0x00, 0x06, 0xFF, 0xFE, 0x00, 0x03, 0x00, 0x00, +0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01, +0x03, 0x0C, 0x30, 0xC3, 0x0A, 0x74, 0x56, 0x2D, 0x0D, 0x62, 0xDB, 0xC7, 0x16, 0xF4, 0xBA, 0x02, +0x38, 0x83, 0xF8, 0x83, 0x30, 0x00, 0xF8, 0x83, 0x25, 0x8E, 0xF8, 0x83, 0x30, 0x00, 0xF8, 0x83, +0xFF, 0xFF, 0xFF, 0xFF, 0x0C, 0xBD, 0xD8, 0x11, 0x24, 0x00, 0x04, 0x00, 0x1A, 0x82, 0x79, 0xA1, +0x00, 0x36, 0x00, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x38, 0x83, 0x6F, 0xA2, +0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00, +0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, +0x1F, 0xA4, 0xE8, 0xE4, 0xFF, 0xF5, 0xDC, 0xB9, 0x00, 0x5B, 0x79, 0xCF, 0x1F, 0x3F, 0x78, 0x76, +0x00, 0x86, 0x7C, 0x5A, 0x00, 0x86, 0x23, 0x47, 0xFA, 0xB9, 0x86, 0x31, 0x00, 0x74, 0x87, 0x8A, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x43, 0x05, 0xFF, 0xFF, 0xE9, 0xA8, 0x00, 0x00, 0x21, 0x82, +0xFA, 0xB8, 0x4D, 0x46, 0xFF, 0xFA, 0xDF, 0x3D, 0xFF, 0xFF, 0xB2, 0xB3, 0x00, 0x00, 0x00, 0x00, +0x3F, 0xFF, 0xBA, 0x98, 0x00, 0x5D, 0xAC, 0x08, 0x00, 0x0A, 0x63, 0x78, 0x00, 0x01, 0x46, 0x21, +0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x42, 0xB5, 0x00, 0x06, 0x00, 0x64, 0x00, 0x64, 0x00, 0x06, +0x14, 0x06, 0x02, 0x9F, 0x0F, 0x47, 0x91, 0x32, 0xD9, 0x0E, 0x9F, 0xC9, 0x1D, 0xCF, 0x4C, 0x34, +0x3B, 0xB6, 0x7A, 0xE8, 0x00, 0x64, 0x00, 0x06, 0x00, 0xC8, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFE, +/* bank # 1 */ +0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x07, 0x00, 0x00, 0xFF, 0xF1, 0x00, 0x00, 0xFA, 0x46, 0x00, 0x00, 0xA2, 0xB8, 0x00, 0x00, +0x10, 0x00, 0x00, 0x00, 0x04, 0xD6, 0x00, 0x00, 0x04, 0xCC, 0x00, 0x00, 0x04, 0xCC, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x06, 0x00, 0x02, 0x00, 0x05, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x05, 0x00, 0x64, 0x00, 0x20, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x03, 0x00, +0x00, 0x00, 0x00, 0x32, 0xF8, 0x98, 0x00, 0x00, 0xFF, 0x65, 0x00, 0x00, 0x83, 0x0F, 0x00, 0x00, +0x00, 0x06, 0x00, 0x00, 0xFF, 0xF1, 0x00, 0x00, 0xFA, 0x46, 0x00, 0x00, 0xA2, 0xB8, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, +0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x0D, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x02, 0x00, 0x00, +0x00, 0x01, 0xFB, 0x83, 0x00, 0x7C, 0x00, 0x00, 0xFB, 0x15, 0xFC, 0x00, 0x1F, 0xB4, 0xFF, 0x83, +0x00, 0x00, 0x00, 0x01, 0x00, 0x65, 0x00, 0x07, 0x00, 0x64, 0x03, 0xE8, 0x00, 0x64, 0x00, 0x28, +0x00, 0x00, 0xFF, 0xFD, 0x00, 0x00, 0x00, 0x00, 0x16, 0xA0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x10, 0x00, 0x00, 0x2F, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF4, 0x00, 0x00, 0x10, 0x00, +/* bank # 2 */ +0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x44, 0x00, 0x01, 0x00, 0x05, 0xBA, 0xC6, 0x00, 0x47, 0x78, 0xA2, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14, +0x00, 0x00, 0x23, 0xBB, 0x00, 0x2E, 0xA2, 0x5B, 0x00, 0x00, 0x05, 0x68, 0x00, 0x0B, 0xCF, 0x49, +0x00, 0x04, 0xFF, 0xFD, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, +0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x64, 0x00, 0x07, 0x00, 0x08, 0x00, 0x06, 0x00, 0x06, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x2E, 0xA2, 0x5B, 0x00, 0x00, 0x05, 0x68, 0x00, 0x0B, 0xCF, 0x49, 0x00, 0x00, 0x00, 0x00, +0x00, 0xF8, 0xF6, 0x2A, 0x3F, 0x68, 0xF5, 0x7A, 0x00, 0x04, 0xFF, 0xFD, 0x00, 0x02, 0x00, 0x00, +0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x0E, +0xFF, 0xFF, 0xFF, 0xCF, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x32, 0xFF, 0xFF, 0xFF, 0x9C, +0x00, 0x00, 0x43, 0x05, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x64, +0xFF, 0xE5, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +/* bank # 3 */ +0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x24, 0x26, 0xD3, +0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3C, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x9E, 0x65, 0x5D, +0x0C, 0x0A, 0x4E, 0x68, 0xCD, 0xCF, 0x77, 0x09, 0x50, 0x16, 0x67, 0x59, 0xC6, 0x19, 0xCE, 0x82, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x71, 0x1C, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0xD7, 0x84, 0x00, 0x03, 0x00, 0x00, 0x00, +0x00, 0x11, 0xDC, 0x47, 0x03, 0x00, 0x00, 0x00, 0xC7, 0x93, 0x8F, 0x9D, 0x1E, 0x1B, 0x1C, 0x19, +0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0E, 0xDF, 0xA4, 0x38, 0x1F, 0x9E, 0x65, 0x5D, +0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x71, 0x1C, 0x02, 0x03, 0x18, 0x85, 0x00, 0x00, 0x40, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x3F, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xF4, 0xC9, 0xFF, 0xFF, 0xBC, 0xF0, 0x00, 0x01, 0x0C, 0x0F, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0xF5, 0xB7, 0xBA, 0xB3, 0x67, 0x7D, 0xDF, 0x7E, 0x72, 0x90, 0x2E, 0x55, 0x4C, 0xF6, 0xE6, 0x88, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +/* bank # 4 */ +0xD8, 0xDC, 0xB4, 0xB8, 0xB0, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xB3, 0xB7, 0xBB, 0x8E, 0x9E, +0xAE, 0xF1, 0x32, 0xF5, 0x1B, 0xF1, 0xB4, 0xB8, 0xB0, 0x80, 0x97, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, +0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0x4C, 0xCD, 0x6C, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0xF1, 0xA9, +0x89, 0x26, 0x46, 0x66, 0xB2, 0x89, 0x99, 0xA9, 0x2D, 0x55, 0x7D, 0xB0, 0xB0, 0x8A, 0xA8, 0x96, +0x36, 0x56, 0x76, 0xF1, 0xBA, 0xA3, 0xB4, 0xB2, 0x80, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB2, 0x83, +0x98, 0xBA, 0xA3, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xB2, 0xB9, 0xB4, 0x98, 0x83, 0xF1, +0xA3, 0x29, 0x55, 0x7D, 0xBA, 0xB5, 0xB1, 0xA3, 0x83, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xB2, +0xB6, 0xAA, 0x83, 0x93, 0x28, 0x54, 0x7C, 0xF1, 0xB9, 0xA3, 0x82, 0x93, 0x61, 0xBA, 0xA2, 0xDA, +0xDE, 0xDF, 0xDB, 0x81, 0x9A, 0xB9, 0xAE, 0xF5, 0x60, 0x68, 0x70, 0xF1, 0xDA, 0xBA, 0xA2, 0xDF, +0xD9, 0xBA, 0xA2, 0xFA, 0xB9, 0xA3, 0x82, 0x92, 0xDB, 0x31, 0xBA, 0xA2, 0xD9, 0xBA, 0xA2, 0xF8, +0xDF, 0x85, 0xA4, 0xD0, 0xC1, 0xBB, 0xAD, 0x83, 0xC2, 0xC5, 0xC7, 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, +0xBA, 0xA0, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xAA, 0xB3, 0x8D, 0xB4, 0x98, 0x0D, 0x35, +0x5D, 0xB2, 0xB6, 0xBA, 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, +0xB8, 0xAA, 0x87, 0x2C, 0x54, 0x7C, 0xBA, 0xA4, 0xB0, 0x8A, 0xB6, 0x91, 0x32, 0x56, 0x76, 0xB2, +0x84, 0x94, 0xA4, 0xC8, 0x08, 0xCD, 0xD8, 0xB8, 0xB4, 0xB0, 0xF1, 0x99, 0x82, 0xA8, 0x2D, 0x55, +0x7D, 0x98, 0xA8, 0x0E, 0x16, 0x1E, 0xA2, 0x2C, 0x54, 0x7C, 0x92, 0xA4, 0xF0, 0x2C, 0x50, 0x78, +/* bank # 5 */ +0xF1, 0x84, 0xA8, 0x98, 0xC4, 0xCD, 0xFC, 0xD8, 0x0D, 0xDB, 0xA8, 0xFC, 0x2D, 0xF3, 0xD9, 0xBA, +0xA6, 0xF8, 0xDA, 0xBA, 0xA6, 0xDE, 0xD8, 0xBA, 0xB2, 0xB6, 0x86, 0x96, 0xA6, 0xD0, 0xF3, 0xC8, +0x41, 0xDA, 0xA6, 0xC8, 0xF8, 0xD8, 0xB0, 0xB4, 0xB8, 0x82, 0xA8, 0x92, 0xF5, 0x2C, 0x54, 0x88, +0x98, 0xF1, 0x35, 0xD9, 0xF4, 0x18, 0xD8, 0xF1, 0xA2, 0xD0, 0xF8, 0xF9, 0xA8, 0x84, 0xD9, 0xC7, +0xDF, 0xF8, 0xF8, 0x83, 0xC5, 0xDA, 0xDF, 0x69, 0xDF, 0x83, 0xC1, 0xD8, 0xF4, 0x01, 0x14, 0xF1, +0xA8, 0x82, 0x4E, 0xA8, 0x84, 0xF3, 0x11, 0xD1, 0x82, 0xF5, 0xD9, 0x92, 0x28, 0x97, 0x88, 0xF1, +0x09, 0xF4, 0x1C, 0x1C, 0xD8, 0x84, 0xA8, 0xF3, 0xC0, 0xF9, 0xD1, 0xD9, 0x97, 0x82, 0xF1, 0x29, +0xF4, 0x0D, 0xD8, 0xF3, 0xF9, 0xF9, 0xD1, 0xD9, 0x82, 0xF4, 0xC2, 0x03, 0xD8, 0xDE, 0xDF, 0x1A, +0xD8, 0xF1, 0xA2, 0xFA, 0xF9, 0xA8, 0x84, 0x98, 0xD9, 0xC7, 0xDF, 0xF8, 0xF8, 0xF8, 0x83, 0xC7, +0xDA, 0xDF, 0x69, 0xDF, 0xF8, 0x83, 0xC3, 0xD8, 0xF4, 0x01, 0x14, 0xF1, 0x98, 0xA8, 0x82, 0x2E, +0xA8, 0x84, 0xF3, 0x11, 0xD1, 0x82, 0xF5, 0xD9, 0x92, 0x50, 0x97, 0x88, 0xF1, 0x09, 0xF4, 0x1C, +0xD8, 0x84, 0xA8, 0xF3, 0xC0, 0xF8, 0xF9, 0xD1, 0xD9, 0x97, 0x82, 0xF1, 0x49, 0xF4, 0x0D, 0xD8, +0xF3, 0xF9, 0xF9, 0xD1, 0xD9, 0x82, 0xF4, 0xC4, 0x03, 0xD8, 0xDE, 0xDF, 0xD8, 0xF1, 0xAD, 0x88, +0x98, 0xCC, 0xA8, 0x09, 0xF9, 0xD9, 0x82, 0x92, 0xA8, 0xF5, 0x7C, 0xF1, 0x88, 0x3A, 0xCF, 0x94, +0x4A, 0x6E, 0x98, 0xDB, 0x69, 0x31, 0xDA, 0xAD, 0xF2, 0xDE, 0xF9, 0xD8, 0x87, 0x95, 0xA8, 0xF2, +0x21, 0xD1, 0xDA, 0xA5, 0xF9, 0xF4, 0x17, 0xD9, 0xF1, 0xAE, 0x8E, 0xD0, 0xC0, 0xC3, 0xAE, 0x82, +/* bank # 6 */ +0xC6, 0x84, 0xC3, 0xA8, 0x85, 0x95, 0xC8, 0xA5, 0x88, 0xF2, 0xC0, 0xF1, 0xF4, 0x01, 0x0E, 0xF1, +0x8E, 0x9E, 0xA8, 0xC6, 0x3E, 0x56, 0xF5, 0x54, 0xF1, 0x88, 0x72, 0xF4, 0x01, 0x15, 0xF1, 0x98, +0x45, 0x85, 0x6E, 0xF5, 0x8E, 0x9E, 0x04, 0x88, 0xF1, 0x42, 0x98, 0x5A, 0x8E, 0x9E, 0x06, 0x88, +0x69, 0xF4, 0x01, 0x1C, 0xF1, 0x98, 0x1E, 0x11, 0x08, 0xD0, 0xF5, 0x04, 0xF1, 0x1E, 0x97, 0x02, +0x02, 0x98, 0x36, 0x25, 0xDB, 0xF9, 0xD9, 0x85, 0xA5, 0xF3, 0xC1, 0xDA, 0x85, 0xA5, 0xF3, 0xDF, +0xD8, 0x85, 0x95, 0xA8, 0xF3, 0x09, 0xDA, 0xA5, 0xFA, 0xD8, 0x82, 0x92, 0xA8, 0xF5, 0x78, 0xF1, +0x88, 0x1A, 0x84, 0x9F, 0x26, 0x88, 0x98, 0x21, 0xDA, 0xF4, 0x1D, 0xF3, 0xD8, 0x87, 0x9F, 0x39, +0xD1, 0xAF, 0xD9, 0xDF, 0xDF, 0xFB, 0xF9, 0xF4, 0x0C, 0xF3, 0xD8, 0xFA, 0xD0, 0xF8, 0xDA, 0xF9, +0xF9, 0xD0, 0xDF, 0xD9, 0xF9, 0xD8, 0xF4, 0x0B, 0xD8, 0xF3, 0x87, 0x9F, 0x39, 0xD1, 0xAF, 0xD9, +0xDF, 0xDF, 0xF4, 0x1D, 0xF3, 0xD8, 0xFA, 0xFC, 0xA8, 0x69, 0xF9, 0xF9, 0xAF, 0xD0, 0xDA, 0xDE, +0xFA, 0xD9, 0xF8, 0x8F, 0x9F, 0xA8, 0xF1, 0xCC, 0xF3, 0x98, 0xDB, 0x45, 0xD9, 0xAF, 0xDF, 0xD0, +0xF8, 0xD8, 0xF1, 0x8F, 0x9F, 0xA8, 0xCA, 0xF3, 0x88, 0x09, 0xDA, 0xAF, 0x8F, 0xCB, 0xF8, 0xD8, +0xF2, 0xAD, 0x97, 0x8D, 0x0C, 0xD9, 0xA5, 0xDF, 0xF9, 0xBA, 0xA6, 0xF3, 0xFA, 0xF4, 0x12, 0xF2, +0xD8, 0x95, 0x0D, 0xD1, 0xD9, 0xBA, 0xA6, 0xF3, 0xFA, 0xDA, 0xA5, 0xF2, 0xC1, 0xBA, 0xA6, 0xF3, +0xDF, 0xD8, 0xF1, 0xBA, 0xB2, 0xB6, 0x86, 0x96, 0xA6, 0xD0, 0xCA, 0xF3, 0x49, 0xDA, 0xA6, 0xCB, +0xF8, 0xD8, 0xB0, 0xB4, 0xB8, 0xD8, 0xAD, 0x84, 0xF2, 0xC0, 0xDF, 0xF1, 0x8F, 0xCB, 0xC3, 0xA8, +/* bank # 7 */ +0xB2, 0xB6, 0x86, 0x96, 0xC8, 0xC1, 0xCB, 0xC3, 0xF3, 0xB0, 0xB4, 0x88, 0x98, 0xA8, 0x21, 0xDB, +0x71, 0x8D, 0x9D, 0x71, 0x85, 0x95, 0x21, 0xD9, 0xAD, 0xF2, 0xFA, 0xD8, 0x85, 0x97, 0xA8, 0x28, +0xD9, 0xF4, 0x08, 0xD8, 0xF2, 0x8D, 0x29, 0xDA, 0xF4, 0x05, 0xD9, 0xF2, 0x85, 0xA4, 0xC2, 0xF2, +0xD8, 0xA8, 0x8D, 0x94, 0x01, 0xD1, 0xD9, 0xF4, 0x11, 0xF2, 0xD8, 0x87, 0x21, 0xD8, 0xF4, 0x0A, +0xD8, 0xF2, 0x84, 0x98, 0xA8, 0xC8, 0x01, 0xD1, 0xD9, 0xF4, 0x11, 0xD8, 0xF3, 0xA4, 0xC8, 0xBB, +0xAF, 0xD0, 0xF2, 0xDE, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xD8, 0xF1, 0xB8, 0xF6, +0xB5, 0xB9, 0xB0, 0x8A, 0x95, 0xA3, 0xDE, 0x3C, 0xA3, 0xD9, 0xF8, 0xD8, 0x5C, 0xA3, 0xD9, 0xF8, +0xD8, 0x7C, 0xA3, 0xD9, 0xF8, 0xD8, 0xF8, 0xF9, 0xD1, 0xA5, 0xD9, 0xDF, 0xDA, 0xFA, 0xD8, 0xB1, +0x85, 0x30, 0xF7, 0xD9, 0xDE, 0xD8, 0xF8, 0x30, 0xAD, 0xDA, 0xDE, 0xD8, 0xF2, 0xB4, 0x8C, 0x99, +0xA3, 0x2D, 0x55, 0x7D, 0xA0, 0x83, 0xDF, 0xDF, 0xDF, 0xB5, 0x91, 0xA0, 0xF6, 0x29, 0xD9, 0xFB, +0xD8, 0xA0, 0xFC, 0x29, 0xD9, 0xFA, 0xD8, 0xA0, 0xD0, 0x51, 0xD9, 0xF8, 0xD8, 0xFC, 0x51, 0xD9, +0xF9, 0xD8, 0x79, 0xD9, 0xFB, 0xD8, 0xA0, 0xD0, 0xFC, 0x79, 0xD9, 0xFA, 0xD8, 0xA1, 0xF9, 0xF9, +0xF9, 0xF9, 0xF9, 0xA0, 0xDA, 0xDF, 0xDF, 0xDF, 0xD8, 0xA1, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xAC, +0xDE, 0xF8, 0xAD, 0xDE, 0x83, 0x93, 0xAC, 0x2C, 0x54, 0x7C, 0xF1, 0xA8, 0xDF, 0xDF, 0xDF, 0xF6, +0x9D, 0x2C, 0xDA, 0xA0, 0xDF, 0xD9, 0xFA, 0xDB, 0x2D, 0xF8, 0xD8, 0xA8, 0x50, 0xDA, 0xA0, 0xD0, +0xDE, 0xD9, 0xD0, 0xF8, 0xF8, 0xF8, 0xDB, 0x55, 0xF8, 0xD8, 0xA8, 0x78, 0xDA, 0xA0, 0xD0, 0xDF, +/* bank # 8 */ +0xD9, 0xD0, 0xFA, 0xF8, 0xF8, 0xF8, 0xF8, 0xDB, 0x7D, 0xF8, 0xD8, 0x9C, 0xA8, 0x8C, 0xF5, 0x30, +0xDB, 0x38, 0xD9, 0xD0, 0xDE, 0xDF, 0xA0, 0xD0, 0xDE, 0xDF, 0xD8, 0xA8, 0x48, 0xDB, 0x58, 0xD9, +0xDF, 0xD0, 0xDE, 0xA0, 0xDF, 0xD0, 0xDE, 0xD8, 0xA8, 0x68, 0xDB, 0x70, 0xD9, 0xDF, 0xDF, 0xA0, +0xDF, 0xDF, 0xD8, 0xF1, 0xA8, 0x88, 0x90, 0x2C, 0x54, 0x7C, 0x98, 0xA8, 0xD0, 0x5C, 0x38, 0xD1, +0xDA, 0xF2, 0xAE, 0x8C, 0xDF, 0xF9, 0xD8, 0xB0, 0x87, 0xA8, 0xC1, 0xC1, 0xB1, 0x88, 0xA8, 0xC6, +0xF9, 0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xA8, +0xF9, 0xDA, 0x36, 0xD8, 0xA8, 0xF9, 0xDA, 0x36, 0xD8, 0xF7, 0x8D, 0x9D, 0xAD, 0xF8, 0x18, 0xDA, +0xF2, 0xAE, 0xDF, 0xD8, 0xF7, 0xAD, 0xFA, 0x30, 0xD9, 0xA4, 0xDE, 0xF9, 0xD8, 0xF2, 0xAE, 0xDE, +0xFA, 0xF9, 0x83, 0xA7, 0xD9, 0xC3, 0xC5, 0xC7, 0xF1, 0x88, 0x9B, 0xA7, 0x7A, 0xAD, 0xF7, 0xDE, +0xDF, 0xA4, 0xF8, 0x84, 0x94, 0x08, 0xA7, 0x97, 0xF3, 0x00, 0xAE, 0xF2, 0x98, 0x19, 0xA4, 0x88, +0xC6, 0xA3, 0x94, 0x88, 0xF6, 0x32, 0xDF, 0xF2, 0x83, 0x93, 0xDB, 0x09, 0xD9, 0xF2, 0xAA, 0xDF, +0xD8, 0xD8, 0xAE, 0xF8, 0xF9, 0xD1, 0xDA, 0xF3, 0xA4, 0xDE, 0xA7, 0xF1, 0x88, 0x9B, 0x7A, 0xD8, +0xF3, 0x84, 0x94, 0xAE, 0x19, 0xF9, 0xDA, 0xAA, 0xF1, 0xDF, 0xD8, 0xA8, 0x81, 0xC0, 0xC3, 0xC5, +0xC7, 0xA3, 0x92, 0x83, 0xF6, 0x28, 0xAD, 0xDE, 0xD9, 0xF8, 0xD8, 0xA3, 0x50, 0xAD, 0xD9, 0xF8, +0xD8, 0xA3, 0x78, 0xAD, 0xD9, 0xF8, 0xD8, 0xF8, 0xF9, 0xD1, 0xA1, 0xDA, 0xDE, 0xC3, 0xC5, 0xC7, +0xD8, 0xA1, 0x81, 0x94, 0xF8, 0x18, 0xF2, 0xB0, 0x89, 0xAC, 0xC3, 0xC5, 0xC7, 0xF1, 0xD8, 0xB8, +/* bank # 9 */ +0xB4, 0xB0, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0, +0x0C, 0x20, 0x14, 0x40, 0xB0, 0xB4, 0xB8, 0xF0, 0xA8, 0x8A, 0x9A, 0x28, 0x50, 0x78, 0xB7, 0x9B, +0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xF1, 0xBB, 0xAB, +0x88, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0xB3, 0x8B, 0xB8, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0xB0, +0x88, 0xB4, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xBB, 0xAB, 0xB3, 0x8B, 0x02, 0x26, 0x46, 0x66, 0xB0, +0xB8, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79, 0x8A, 0x24, 0x70, 0x59, +0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68, 0x8A, 0x64, 0x48, 0x31, +0x8B, 0x30, 0x49, 0x60, 0x88, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04, 0x28, +0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66, 0xF0, +0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xA9, +0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60, 0x8C, +0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76, 0x7E, +0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB5, 0xB9, 0xA3, 0xDF, 0xDF, 0xDF, 0xAE, 0xD0, +0xDF, 0xAA, 0xD0, 0xDE, 0xF2, 0xAB, 0xF8, 0xF9, 0xD9, 0xB0, 0x87, 0xC4, 0xAA, 0xF1, 0xDF, 0xDF, +0xBB, 0xAF, 0xDF, 0xDF, 0xB9, 0xD8, 0xB1, 0xF1, 0xA3, 0x97, 0x8E, 0x60, 0xDF, 0xB0, 0x84, 0xF2, +0xC8, 0xF8, 0xF9, 0xD9, 0xDE, 0xD8, 0x93, 0x85, 0xF1, 0x4A, 0xB1, 0x83, 0xA3, 0x08, 0xB5, 0x83, +/* bank # 10 */ +0x9A, 0x08, 0x10, 0xB7, 0x9F, 0x10, 0xD8, 0xF1, 0xB0, 0xBA, 0xAE, 0xB0, 0x8A, 0xC2, 0xB2, 0xB6, +0x8E, 0x9E, 0xF1, 0xFB, 0xD9, 0xF4, 0x1D, 0xD8, 0xF9, 0xD9, 0x0C, 0xF1, 0xD8, 0xF8, 0xF8, 0xAD, +0x61, 0xD9, 0xAE, 0xFB, 0xD8, 0xF4, 0x0C, 0xF1, 0xD8, 0xF8, 0xF8, 0xAD, 0x19, 0xD9, 0xAE, 0xFB, +0xDF, 0xD8, 0xF4, 0x16, 0xF1, 0xD8, 0xF8, 0xAD, 0x8D, 0x61, 0xD9, 0xF4, 0xF4, 0xAC, 0xF5, 0x9C, +0x9C, 0x8D, 0xDF, 0x2B, 0xBA, 0xB6, 0xAE, 0xFA, 0xF8, 0xF4, 0x0B, 0xD8, 0xF1, 0xAE, 0xD0, 0xF8, +0xAD, 0x51, 0xDA, 0xAE, 0xFA, 0xF8, 0xF1, 0xD8, 0xB9, 0xB1, 0xB6, 0xA3, 0x83, 0x9C, 0x08, 0xB9, +0xB1, 0x83, 0x9A, 0xB5, 0xAA, 0xC0, 0xFD, 0x30, 0x83, 0xB7, 0x9F, 0x10, 0xB5, 0x8B, 0x93, 0xF2, +0x02, 0x02, 0xD1, 0xAB, 0xDA, 0xDE, 0xD8, 0xF1, 0xB0, 0x80, 0xBA, 0xAB, 0xC0, 0xC3, 0xB2, 0x84, +0xC1, 0xC3, 0xD8, 0xB1, 0xB9, 0xF3, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0, +0x87, 0x9C, 0xB9, 0xA3, 0xDD, 0xF1, 0xB3, 0x8B, 0x8B, 0x8B, 0x8B, 0x8B, 0xB0, 0x87, 0x20, 0x28, +0x30, 0x38, 0xB2, 0x8B, 0xB6, 0x9B, 0xF2, 0xA3, 0xC0, 0xC8, 0xC2, 0xC4, 0xCC, 0xC6, 0xA3, 0xA3, +0xA3, 0xF1, 0xB0, 0x87, 0xB5, 0x9A, 0xD8, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC, 0xBA, 0xAC, 0xDF, 0xB9, //Reverted back as packet size changes causing isues... TODO:change 2742 from 0xD8 to 0x20 Including the DMP_FEATURE_TAP -- known issue in which if you do not enable DMP_FEATURE_TAP then the interrupts will be at 200Hz even if fifo rate +0xA3, 0xFE, 0xF2, 0xAB, 0xC4, 0xAA, 0xF1, 0xDF, 0xDF, 0xBB, 0xAF, 0xDF, 0xDF, 0xA3, 0xA3, 0xA3, +0xD8, 0xD8, 0xD8, 0xBB, 0xB3, 0xB7, 0xF1, 0xAA, 0xF9, 0xDA, 0xFF, 0xD9, 0x80, 0x9A, 0xAA, 0x28, +0xB4, 0x80, 0x98, 0xA7, 0x20, 0xB7, 0x97, 0x87, 0xA8, 0x66, 0x88, 0xF0, 0x79, 0x51, 0xF1, 0x90, +0x2C, 0x87, 0x0C, 0xA7, 0x81, 0x97, 0x62, 0x93, 0xF0, 0x71, 0x71, 0x60, 0x85, 0x94, 0x01, 0x29, +/* bank # 11 */ +0x51, 0x79, 0x90, 0xA5, 0xF1, 0x28, 0x4C, 0x6C, 0x87, 0x0C, 0x95, 0x18, 0x85, 0x78, 0xA3, 0x83, +0x90, 0x28, 0x4C, 0x6C, 0x88, 0x6C, 0xD8, 0xF3, 0xA2, 0x82, 0x00, 0xF2, 0x10, 0xA8, 0x92, 0x19, +0x80, 0xA2, 0xF2, 0xD9, 0x26, 0xD8, 0xF1, 0x88, 0xA8, 0x4D, 0xD9, 0x48, 0xD8, 0x96, 0xA8, 0x39, +0x80, 0xD9, 0x3C, 0xD8, 0x95, 0x80, 0xA8, 0x39, 0xA6, 0x86, 0x98, 0xD9, 0x2C, 0xDA, 0x87, 0xA7, +0x2C, 0xD8, 0xA8, 0x89, 0x95, 0x19, 0xA9, 0x80, 0xD9, 0x38, 0xD8, 0xA8, 0x89, 0x39, 0xA9, 0x80, +0xDA, 0x3C, 0xD8, 0xA8, 0x2E, 0xA8, 0x39, 0x90, 0xD9, 0x0C, 0xD8, 0xA8, 0x95, 0x31, 0x98, 0xD9, +0x0C, 0xD8, 0xA8, 0x09, 0xD9, 0xFF, 0xD8, 0x01, 0xDA, 0xFF, 0xD8, 0x95, 0x39, 0xA9, 0xDA, 0x26, +0xFF, 0xD8, 0x90, 0xA8, 0x0D, 0x89, 0x99, 0xA8, 0x10, 0x80, 0x98, 0x21, 0xDA, 0x2E, 0xD8, 0x89, +0x99, 0xA8, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8, 0x86, 0x96, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8, +0x87, 0x31, 0x80, 0xDA, 0x2E, 0xD8, 0xA8, 0x82, 0x92, 0xF3, 0x41, 0x80, 0xF1, 0xD9, 0x2E, 0xD8, +0xA8, 0x82, 0xF3, 0x19, 0x80, 0xF1, 0xD9, 0x2E, 0xD8, 0x82, 0xAC, 0xF3, 0xC0, 0xA2, 0x80, 0x22, +0xF1, 0xA6, 0x2E, 0xA7, 0x2E, 0xA9, 0x22, 0x98, 0xA8, 0x29, 0xDA, 0xAC, 0xDE, 0xFF, 0xD8, 0xA2, +0xF2, 0x2A, 0xF1, 0xA9, 0x2E, 0x82, 0x92, 0xA8, 0xF2, 0x31, 0x80, 0xA6, 0x96, 0xF1, 0xD9, 0x00, +0xAC, 0x8C, 0x9C, 0x0C, 0x30, 0xAC, 0xDE, 0xD0, 0xDE, 0xFF, 0xD8, 0x8C, 0x9C, 0xAC, 0xD0, 0x10, +0xAC, 0xDE, 0x80, 0x92, 0xA2, 0xF2, 0x4C, 0x82, 0xA8, 0xF1, 0xCA, 0xF2, 0x35, 0xF1, 0x96, 0x88, +0xA6, 0xD9, 0x00, 0xD8, 0xF1, 0xFF, +}; + + +static const uint8_t dmpCode20[] = { + /* bank # 0 */ + 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x40, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCB, 0x47, 0xA2, 0x20, 0x00, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82, + 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC, + 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4, + 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10, + /* bank # 1 */ + 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8, + 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C, + 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x09, 0x23, 0xA1, 0x35, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C, + 0x80, 0x00, 0xFF, 0xFF, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, + 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0, + /* bank # 2 */ + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x01, 0x00, 0x05, 0x8B, 0xC1, 0x00, 0x00, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + /* bank # 3 */ + 0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F, + 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, + 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, + 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, + 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, + 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, + 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, + 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0x4C, 0xCD, 0x6C, 0xA9, 0x0C, + 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, + 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, + 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, + 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, + 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0, + 0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86, + 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1, + 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86, + /* bank # 4 */ + 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA, + 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C, + 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8, + 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3, + 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84, + 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5, + 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3, + 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1, + 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5, + 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A, + 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8, + 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87, + /* bank # 5 */ + 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8, + 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68, + 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D, + 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94, + 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA, + 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56, + 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, + 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA, + 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A, + 0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60, + 0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, + 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, + 0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, + 0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79, + 0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68, + 0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68, + /* bank # 6 */ + 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04, + 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66, + 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, + 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60, + 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76, + 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56, + 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD, + 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91, + 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, + 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE, + 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9, + 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD, + 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E, + 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8, + 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89, + 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79, + /* bank # 7 */ + 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8, + 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA, + 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB, + 0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3, + 0xDD, 0xF1, 0x20, 0x28, 0x30, 0x38, 0x9A, 0xF1, 0x28, 0x30, 0x38, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3, + 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, + 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0x28, 0x30, 0x38, + 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0x30, 0xDC, + 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xFE, 0xD8, 0xFF, +}; diff --git a/fw/rbcx-coprocessor/include/MpuDriver.hpp b/fw/rbcx-coprocessor/include/MpuDriver.hpp new file mode 100644 index 00000000..ecbbf6ac --- /dev/null +++ b/fw/rbcx-coprocessor/include/MpuDriver.hpp @@ -0,0 +1,796 @@ +// I2Cdev library collection - mpu 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 +// 2017-03-11 - tested basic functions on STM32 + +// 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 _mpu_H_ +#define _mpu_H_ + +#include +#include + +#if ((defined mpu_INCLUDE_DMP_MOTIONAPPS20) \ + || (defined mpu_INCLUDE_DMP_MOTIONAPPS41)) +#error DMP is not supported yet +#endif + +#define mpu_ADDRESS_AD0_LOW \ + 0x68 // address pin low (GND), default for InvenSense evaluation board +#define mpu_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC) +#define mpu_DEFAULT_ADDRESS mpu_ADDRESS_AD0_LOW + +#define mpu_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD +#define mpu_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD +#define mpu_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD +#define mpu_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN +#define mpu_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN +#define mpu_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN +#define mpu_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS +#define mpu_RA_XA_OFFS_L_TC 0x07 +#define mpu_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS +#define mpu_RA_YA_OFFS_L_TC 0x09 +#define mpu_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS +#define mpu_RA_ZA_OFFS_L_TC 0x0B +#define mpu_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR +#define mpu_RA_XG_OFFS_USRL 0x14 +#define mpu_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR +#define mpu_RA_YG_OFFS_USRL 0x16 +#define mpu_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR +#define mpu_RA_ZG_OFFS_USRL 0x18 +#define mpu_RA_SMPLRT_DIV 0x19 +#define mpu_RA_CONFIG 0x1A +#define mpu_RA_GYRO_CONFIG 0x1B +#define mpu_RA_ACCEL_CONFIG 0x1C +#define mpu_RA_FF_THR 0x1D +#define mpu_RA_FF_DUR 0x1E +#define mpu_RA_MOT_THR 0x1F +#define mpu_RA_MOT_DUR 0x20 +#define mpu_RA_ZRMOT_THR 0x21 +#define mpu_RA_ZRMOT_DUR 0x22 +#define mpu_RA_FIFO_EN 0x23 +#define mpu_RA_I2C_MST_CTRL 0x24 +#define mpu_RA_I2C_SLV0_ADDR 0x25 +#define mpu_RA_I2C_SLV0_REG 0x26 +#define mpu_RA_I2C_SLV0_CTRL 0x27 +#define mpu_RA_I2C_SLV1_ADDR 0x28 +#define mpu_RA_I2C_SLV1_REG 0x29 +#define mpu_RA_I2C_SLV1_CTRL 0x2A +#define mpu_RA_I2C_SLV2_ADDR 0x2B +#define mpu_RA_I2C_SLV2_REG 0x2C +#define mpu_RA_I2C_SLV2_CTRL 0x2D +#define mpu_RA_I2C_SLV3_ADDR 0x2E +#define mpu_RA_I2C_SLV3_REG 0x2F +#define mpu_RA_I2C_SLV3_CTRL 0x30 +#define mpu_RA_I2C_SLV4_ADDR 0x31 +#define mpu_RA_I2C_SLV4_REG 0x32 +#define mpu_RA_I2C_SLV4_DO 0x33 +#define mpu_RA_I2C_SLV4_CTRL 0x34 +#define mpu_RA_I2C_SLV4_DI 0x35 +#define mpu_RA_I2C_MST_STATUS 0x36 +#define mpu_RA_INT_PIN_CFG 0x37 +#define mpu_RA_INT_ENABLE 0x38 +#define mpu_RA_DMP_INT_STATUS 0x39 +#define mpu_RA_INT_STATUS 0x3A +#define mpu_RA_ACCEL_XOUT_H 0x3B +#define mpu_RA_ACCEL_XOUT_L 0x3C +#define mpu_RA_ACCEL_YOUT_H 0x3D +#define mpu_RA_ACCEL_YOUT_L 0x3E +#define mpu_RA_ACCEL_ZOUT_H 0x3F +#define mpu_RA_ACCEL_ZOUT_L 0x40 +#define mpu_RA_TEMP_OUT_H 0x41 +#define mpu_RA_TEMP_OUT_L 0x42 +#define mpu_RA_GYRO_XOUT_H 0x43 +#define mpu_RA_GYRO_XOUT_L 0x44 +#define mpu_RA_GYRO_YOUT_H 0x45 +#define mpu_RA_GYRO_YOUT_L 0x46 +#define mpu_RA_GYRO_ZOUT_H 0x47 +#define mpu_RA_GYRO_ZOUT_L 0x48 +#define mpu_RA_EXT_SENS_DATA_00 0x49 +#define mpu_RA_EXT_SENS_DATA_01 0x4A +#define mpu_RA_EXT_SENS_DATA_02 0x4B +#define mpu_RA_EXT_SENS_DATA_03 0x4C +#define mpu_RA_EXT_SENS_DATA_04 0x4D +#define mpu_RA_EXT_SENS_DATA_05 0x4E +#define mpu_RA_EXT_SENS_DATA_06 0x4F +#define mpu_RA_EXT_SENS_DATA_07 0x50 +#define mpu_RA_EXT_SENS_DATA_08 0x51 +#define mpu_RA_EXT_SENS_DATA_09 0x52 +#define mpu_RA_EXT_SENS_DATA_10 0x53 +#define mpu_RA_EXT_SENS_DATA_11 0x54 +#define mpu_RA_EXT_SENS_DATA_12 0x55 +#define mpu_RA_EXT_SENS_DATA_13 0x56 +#define mpu_RA_EXT_SENS_DATA_14 0x57 +#define mpu_RA_EXT_SENS_DATA_15 0x58 +#define mpu_RA_EXT_SENS_DATA_16 0x59 +#define mpu_RA_EXT_SENS_DATA_17 0x5A +#define mpu_RA_EXT_SENS_DATA_18 0x5B +#define mpu_RA_EXT_SENS_DATA_19 0x5C +#define mpu_RA_EXT_SENS_DATA_20 0x5D +#define mpu_RA_EXT_SENS_DATA_21 0x5E +#define mpu_RA_EXT_SENS_DATA_22 0x5F +#define mpu_RA_EXT_SENS_DATA_23 0x60 +#define mpu_RA_MOT_DETECT_STATUS 0x61 +#define mpu_RA_I2C_SLV0_DO 0x63 +#define mpu_RA_I2C_SLV1_DO 0x64 +#define mpu_RA_I2C_SLV2_DO 0x65 +#define mpu_RA_I2C_SLV3_DO 0x66 +#define mpu_RA_I2C_MST_DELAY_CTRL 0x67 +#define mpu_RA_SIGNAL_PATH_RESET 0x68 +#define mpu_RA_MOT_DETECT_CTRL 0x69 +#define mpu_RA_USER_CTRL 0x6A +#define mpu_RA_PWR_MGMT_1 0x6B +#define mpu_RA_PWR_MGMT_2 0x6C +#define mpu_RA_BANK_SEL 0x6D +#define mpu_RA_MEM_START_ADDR 0x6E +#define mpu_RA_MEM_R_W 0x6F +#define mpu_RA_DMP_CFG_1 0x70 +#define mpu_RA_DMP_CFG_2 0x71 +#define mpu_RA_FIFO_COUNTH 0x72 +#define mpu_RA_FIFO_COUNTL 0x73 +#define mpu_RA_FIFO_R_W 0x74 +#define mpu_RA_WHO_AM_I 0x75 + +#define mpu_TC_PWR_MODE_BIT 7 +#define mpu_TC_OFFSET_BIT 6 +#define mpu_TC_OFFSET_LENGTH 6 +#define mpu_TC_OTP_BNK_VLD_BIT 0 + +#define mpu_VDDIO_LEVEL_VLOGIC 0 +#define mpu_VDDIO_LEVEL_VDD 1 + +#define mpu_CFG_EXT_SYNC_SET_BIT 5 +#define mpu_CFG_EXT_SYNC_SET_LENGTH 3 +#define mpu_CFG_DLPF_CFG_BIT 2 +#define mpu_CFG_DLPF_CFG_LENGTH 3 + +#define mpu_EXT_SYNC_DISABLED 0x0 +#define mpu_EXT_SYNC_TEMP_OUT_L 0x1 +#define mpu_EXT_SYNC_GYRO_XOUT_L 0x2 +#define mpu_EXT_SYNC_GYRO_YOUT_L 0x3 +#define mpu_EXT_SYNC_GYRO_ZOUT_L 0x4 +#define mpu_EXT_SYNC_ACCEL_XOUT_L 0x5 +#define mpu_EXT_SYNC_ACCEL_YOUT_L 0x6 +#define mpu_EXT_SYNC_ACCEL_ZOUT_L 0x7 + +#define mpu_DLPF_BW_256 0x00 +#define mpu_DLPF_BW_188 0x01 +#define mpu_DLPF_BW_98 0x02 +#define mpu_DLPF_BW_42 0x03 +#define mpu_DLPF_BW_20 0x04 +#define mpu_DLPF_BW_10 0x05 +#define mpu_DLPF_BW_5 0x06 + +#define mpu_GCONFIG_FS_SEL_BIT 4 +#define mpu_GCONFIG_FS_SEL_LENGTH 2 + +#define mpu_GYRO_FS_250 0x00 +#define mpu_GYRO_FS_500 0x01 +#define mpu_GYRO_FS_1000 0x02 +#define mpu_GYRO_FS_2000 0x03 + +#define mpu_ACONFIG_XA_ST_BIT 7 +#define mpu_ACONFIG_YA_ST_BIT 6 +#define mpu_ACONFIG_ZA_ST_BIT 5 +#define mpu_ACONFIG_AFS_SEL_BIT 4 +#define mpu_ACONFIG_AFS_SEL_LENGTH 2 +#define mpu_ACONFIG_ACCEL_HPF_BIT 2 +#define mpu_ACONFIG_ACCEL_HPF_LENGTH 3 + +#define mpu_ACCEL_FS_2 0x00 +#define mpu_ACCEL_FS_4 0x01 +#define mpu_ACCEL_FS_8 0x02 +#define mpu_ACCEL_FS_16 0x03 + +#define mpu_DHPF_RESET 0x00 +#define mpu_DHPF_5 0x01 +#define mpu_DHPF_2P5 0x02 +#define mpu_DHPF_1P25 0x03 +#define mpu_DHPF_0P63 0x04 +#define mpu_DHPF_HOLD 0x07 + +#define mpu_TEMP_FIFO_EN_BIT 7 +#define mpu_XG_FIFO_EN_BIT 6 +#define mpu_YG_FIFO_EN_BIT 5 +#define mpu_ZG_FIFO_EN_BIT 4 +#define mpu_ACCEL_FIFO_EN_BIT 3 +#define mpu_SLV2_FIFO_EN_BIT 2 +#define mpu_SLV1_FIFO_EN_BIT 1 +#define mpu_SLV0_FIFO_EN_BIT 0 + +#define mpu_MULT_MST_EN_BIT 7 +#define mpu_WAIT_FOR_ES_BIT 6 +#define mpu_SLV_3_FIFO_EN_BIT 5 +#define mpu_I2C_MST_P_NSR_BIT 4 +#define mpu_I2C_MST_CLK_BIT 3 +#define mpu_I2C_MST_CLK_LENGTH 4 + +#define mpu_CLOCK_DIV_348 0x0 +#define mpu_CLOCK_DIV_333 0x1 +#define mpu_CLOCK_DIV_320 0x2 +#define mpu_CLOCK_DIV_308 0x3 +#define mpu_CLOCK_DIV_296 0x4 +#define mpu_CLOCK_DIV_286 0x5 +#define mpu_CLOCK_DIV_276 0x6 +#define mpu_CLOCK_DIV_267 0x7 +#define mpu_CLOCK_DIV_258 0x8 +#define mpu_CLOCK_DIV_500 0x9 +#define mpu_CLOCK_DIV_471 0xA +#define mpu_CLOCK_DIV_444 0xB +#define mpu_CLOCK_DIV_421 0xC +#define mpu_CLOCK_DIV_400 0xD +#define mpu_CLOCK_DIV_381 0xE +#define mpu_CLOCK_DIV_364 0xF + +#define mpu_I2C_SLV_RW_BIT 7 +#define mpu_I2C_SLV_ADDR_BIT 6 +#define mpu_I2C_SLV_ADDR_LENGTH 7 +#define mpu_I2C_SLV_EN_BIT 7 +#define mpu_I2C_SLV_BYTE_SW_BIT 6 +#define mpu_I2C_SLV_REG_DIS_BIT 5 +#define mpu_I2C_SLV_GRP_BIT 4 +#define mpu_I2C_SLV_LEN_BIT 3 +#define mpu_I2C_SLV_LEN_LENGTH 4 + +#define mpu_I2C_SLV4_RW_BIT 7 +#define mpu_I2C_SLV4_ADDR_BIT 6 +#define mpu_I2C_SLV4_ADDR_LENGTH 7 +#define mpu_I2C_SLV4_EN_BIT 7 +#define mpu_I2C_SLV4_INT_EN_BIT 6 +#define mpu_I2C_SLV4_REG_DIS_BIT 5 +#define mpu_I2C_SLV4_MST_DLY_BIT 4 +#define mpu_I2C_SLV4_MST_DLY_LENGTH 5 + +#define mpu_MST_PASS_THROUGH_BIT 7 +#define mpu_MST_I2C_SLV4_DONE_BIT 6 +#define mpu_MST_I2C_LOST_ARB_BIT 5 +#define mpu_MST_I2C_SLV4_NACK_BIT 4 +#define mpu_MST_I2C_SLV3_NACK_BIT 3 +#define mpu_MST_I2C_SLV2_NACK_BIT 2 +#define mpu_MST_I2C_SLV1_NACK_BIT 1 +#define mpu_MST_I2C_SLV0_NACK_BIT 0 + +#define mpu_INTCFG_INT_LEVEL_BIT 7 +#define mpu_INTCFG_INT_OPEN_BIT 6 +#define mpu_INTCFG_LATCH_INT_EN_BIT 5 +#define mpu_INTCFG_INT_RD_CLEAR_BIT 4 +#define mpu_INTCFG_FSYNC_INT_LEVEL_BIT 3 +#define mpu_INTCFG_FSYNC_INT_EN_BIT 2 +#define mpu_INTCFG_I2C_BYPASS_EN_BIT 1 +#define mpu_INTCFG_CLKOUT_EN_BIT 0 + +#define mpu_INTMODE_ACTIVEHIGH 0x00 +#define mpu_INTMODE_ACTIVELOW 0x01 + +#define mpu_INTDRV_PUSHPULL 0x00 +#define mpu_INTDRV_OPENDRAIN 0x01 + +#define mpu_INTLATCH_50USPULSE 0x00 +#define mpu_INTLATCH_WAITCLEAR 0x01 + +#define mpu_INTCLEAR_STATUSREAD 0x00 +#define mpu_INTCLEAR_ANYREAD 0x01 + +#define mpu_INTERRUPT_FF_BIT 7 +#define mpu_INTERRUPT_MOT_BIT 6 +#define mpu_INTERRUPT_ZMOT_BIT 5 +#define mpu_INTERRUPT_FIFO_OFLOW_BIT 4 +#define mpu_INTERRUPT_I2C_MST_INT_BIT 3 +#define mpu_INTERRUPT_PLL_RDY_INT_BIT 2 +#define mpu_INTERRUPT_DMP_INT_BIT 1 +#define mpu_INTERRUPT_DATA_RDY_BIT 0 + +// TODO: figure out what these actually do +// UMPL source code is not very obivous +#define mpu_DMPINT_5_BIT 5 +#define mpu_DMPINT_4_BIT 4 +#define mpu_DMPINT_3_BIT 3 +#define mpu_DMPINT_2_BIT 2 +#define mpu_DMPINT_1_BIT 1 +#define mpu_DMPINT_0_BIT 0 + +#define mpu_MOTION_MOT_XNEG_BIT 7 +#define mpu_MOTION_MOT_XPOS_BIT 6 +#define mpu_MOTION_MOT_YNEG_BIT 5 +#define mpu_MOTION_MOT_YPOS_BIT 4 +#define mpu_MOTION_MOT_ZNEG_BIT 3 +#define mpu_MOTION_MOT_ZPOS_BIT 2 +#define mpu_MOTION_MOT_ZRMOT_BIT 0 + +#define mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT 7 +#define mpu_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4 +#define mpu_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3 +#define mpu_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2 +#define mpu_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1 +#define mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0 + +#define mpu_PATHRESET_GYRO_RESET_BIT 2 +#define mpu_PATHRESET_ACCEL_RESET_BIT 1 +#define mpu_PATHRESET_TEMP_RESET_BIT 0 + +#define mpu_DETECT_ACCEL_ON_DELAY_BIT 5 +#define mpu_DETECT_ACCEL_ON_DELAY_LENGTH 2 +#define mpu_DETECT_FF_COUNT_BIT 3 +#define mpu_DETECT_FF_COUNT_LENGTH 2 +#define mpu_DETECT_MOT_COUNT_BIT 1 +#define mpu_DETECT_MOT_COUNT_LENGTH 2 + +#define mpu_DETECT_DECREMENT_RESET 0x0 +#define mpu_DETECT_DECREMENT_1 0x1 +#define mpu_DETECT_DECREMENT_2 0x2 +#define mpu_DETECT_DECREMENT_4 0x3 + +#define mpu_USERCTRL_DMP_EN_BIT 7 +#define mpu_USERCTRL_FIFO_EN_BIT 6 +#define mpu_USERCTRL_I2C_MST_EN_BIT 5 +#define mpu_USERCTRL_I2C_IF_DIS_BIT 4 +#define mpu_USERCTRL_DMP_RESET_BIT 3 +#define mpu_USERCTRL_FIFO_RESET_BIT 2 +#define mpu_USERCTRL_I2C_MST_RESET_BIT 1 +#define mpu_USERCTRL_SIG_COND_RESET_BIT 0 + +#define mpu_PWR1_DEVICE_RESET_BIT 7 +#define mpu_PWR1_SLEEP_BIT 6 +#define mpu_PWR1_CYCLE_BIT 5 +#define mpu_PWR1_TEMP_DIS_BIT 3 +#define mpu_PWR1_CLKSEL_BIT 2 +#define mpu_PWR1_CLKSEL_LENGTH 3 + +#define mpu_CLOCK_INTERNAL 0x00 +#define mpu_CLOCK_PLL_XGYRO 0x01 +#define mpu_CLOCK_PLL_YGYRO 0x02 +#define mpu_CLOCK_PLL_ZGYRO 0x03 +#define mpu_CLOCK_PLL_EXT32K 0x04 +#define mpu_CLOCK_PLL_EXT19M 0x05 +#define mpu_CLOCK_KEEP_RESET 0x07 + +#define mpu_PWR2_LP_WAKE_CTRL_BIT 7 +#define mpu_PWR2_LP_WAKE_CTRL_LENGTH 2 +#define mpu_PWR2_STBY_XA_BIT 5 +#define mpu_PWR2_STBY_YA_BIT 4 +#define mpu_PWR2_STBY_ZA_BIT 3 +#define mpu_PWR2_STBY_XG_BIT 2 +#define mpu_PWR2_STBY_YG_BIT 1 +#define mpu_PWR2_STBY_ZG_BIT 0 + +#define mpu_WAKE_FREQ_1P25 0x0 +#define mpu_WAKE_FREQ_2P5 0x1 +#define mpu_WAKE_FREQ_5 0x2 +#define mpu_WAKE_FREQ_10 0x3 + +#define mpu_BANKSEL_PRFTCH_EN_BIT 6 +#define mpu_BANKSEL_CFG_USER_BANK_BIT 5 +#define mpu_BANKSEL_MEM_SEL_BIT 4 +#define mpu_BANKSEL_MEM_SEL_LENGTH 5 + +#define mpu_WHO_AM_I_BIT 6 +#define mpu_WHO_AM_I_LENGTH 6 + +#define mpu_DMP_MEMORY_BANKS 8 +#define mpu_DMP_MEMORY_BANK_SIZE 256 +#define mpu_DMP_MEMORY_CHUNK_SIZE 16 + +// note: DMP code memory blocks defined at end of header file + +// #define COMPRESS_COEF 4 + +typedef struct mpu_t { + uint8_t devAddr; + uint8_t buffer[14]; +} mpu_t; + +extern mpu_t mpu6050; + +bool mpu_testConnection(); + +// AUX_VDDIO register +uint8_t mpu_getAuxVDDIOLevel(); +void mpu_setAuxVDDIOLevel(uint8_t level); + +// SMPLRT_DIV register +uint8_t mpu_getRate(); +void mpu_setRate(uint8_t rate); + +// CONFIG register +uint8_t mpu_getExternalFrameSync(); +void mpu_setExternalFrameSync(uint8_t sync); +uint8_t mpu_getDLPFMode(); +void mpu_setDLPFMode(uint8_t bandwidth); + +// GYRO_CONFIG register +uint8_t mpu_getFullScaleGyroRange(); +void mpu_setFullScaleGyroRange(uint8_t range); + +// ACCEL_CONFIG register +bool mpu_getAccelXSelfTest(); +void mpu_setAccelXSelfTest(bool enabled); +bool mpu_getAccelYSelfTest(); +void mpu_setAccelYSelfTest(bool enabled); +bool mpu_getAccelZSelfTest(); +void mpu_setAccelZSelfTest(bool enabled); +uint8_t mpu_getFullScaleAccelRange(); +void mpu_setFullScaleAccelRange(uint8_t range); +uint8_t mpu_getDHPFMode(); +void mpu_setDHPFMode(uint8_t mode); + +// FF_THR register +uint8_t mpu_getFreefallDetectionThreshold(); +void mpu_setFreefallDetectionThreshold(uint8_t threshold); + +// FF_DUR register +uint8_t mpu_getFreefallDetectionDuration(); +void mpu_setFreefallDetectionDuration(uint8_t duration); + +// MOT_THR register +uint8_t mpu_getMotionDetectionThreshold(); +void mpu_setMotionDetectionThreshold(uint8_t threshold); + +// MOT_DUR register +uint8_t mpu_getMotionDetectionDuration(); +void mpu_setMotionDetectionDuration(uint8_t duration); + +// ZRMOT_THR register +uint8_t mpu_getZeroMotionDetectionThreshold(); +void mpu_setZeroMotionDetectionThreshold(uint8_t threshold); + +// ZRMOT_DUR register +uint8_t mpu_getZeroMotionDetectionDuration(); +void mpu_setZeroMotionDetectionDuration(uint8_t duration); + +// FIFO_EN register +bool mpu_getTempFIFOEnabled(); +void mpu_setTempFIFOEnabled(bool enabled); +bool mpu_getXGyroFIFOEnabled(); +void mpu_setXGyroFIFOEnabled(bool enabled); +bool mpu_getYGyroFIFOEnabled(); +void mpu_setYGyroFIFOEnabled(bool enabled); +bool mpu_getZGyroFIFOEnabled(); +void mpu_setZGyroFIFOEnabled(bool enabled); +bool mpu_getAccelFIFOEnabled(); +void mpu_setAccelFIFOEnabled(bool enabled); +bool mpu_getSlave2FIFOEnabled(); +void mpu_setSlave2FIFOEnabled(bool enabled); +bool mpu_getSlave1FIFOEnabled(); +void mpu_setSlave1FIFOEnabled(bool enabled); +bool mpu_getSlave0FIFOEnabled(); +void mpu_setSlave0FIFOEnabled(bool enabled); + +// I2C_MST_CTRL register +bool mpu_getMultiMasterEnabled(); +void mpu_setMultiMasterEnabled(bool enabled); +bool mpu_getWaitForExternalSensorEnabled(); +void mpu_setWaitForExternalSensorEnabled(bool enabled); +bool mpu_getSlave3FIFOEnabled(); +void mpu_setSlave3FIFOEnabled(bool enabled); +bool mpu_getSlaveReadWriteTransitionEnabled(); +void mpu_setSlaveReadWriteTransitionEnabled(bool enabled); +uint8_t mpu_getMasterClockSpeed(); +void mpu_setMasterClockSpeed(uint8_t speed); + +// I2C_SLV* registers (Slave 0-3) +uint8_t mpu_getSlaveAddress(uint8_t num); +void mpu_setSlaveAddress(uint8_t num, uint8_t address); +uint8_t mpu_getSlaveRegister(uint8_t num); +void mpu_setSlaveRegister(uint8_t num, uint8_t reg); +bool mpu_getSlaveEnabled(uint8_t num); +void mpu_setSlaveEnabled(uint8_t num, bool enabled); +bool mpu_getSlaveWordByteSwap(uint8_t num); +void mpu_setSlaveWordByteSwap(uint8_t num, bool enabled); +bool mpu_getSlaveWriteMode(uint8_t num); +void mpu_setSlaveWriteMode(uint8_t num, bool mode); +bool mpu_getSlaveWordGroupOffset(uint8_t num); +void mpu_setSlaveWordGroupOffset(uint8_t num, bool enabled); +uint8_t mpu_getSlaveDataLength(uint8_t num); +void mpu_setSlaveDataLength(uint8_t num, uint8_t length); + +// I2C_SLV* registers (Slave 4) +uint8_t mpu_getSlave4Address(); +void mpu_setSlave4Address(uint8_t address); +uint8_t mpu_getSlave4Register(); +void mpu_setSlave4Register(uint8_t reg); +void mpu_setSlave4OutputByte(uint8_t data); +bool mpu_getSlave4Enabled(); +void mpu_setSlave4Enabled(bool enabled); +bool mpu_getSlave4InterruptEnabled(); +void mpu_setSlave4InterruptEnabled(bool enabled); +bool mpu_getSlave4WriteMode(); +void mpu_setSlave4WriteMode(bool mode); +uint8_t mpu_getSlave4MasterDelay(); +void mpu_setSlave4MasterDelay(uint8_t delay); +uint8_t mpu_getSlate4InputByte(); + +// I2C_MST_STATUS register +bool mpu_getPassthroughStatus(); +bool mpu_getSlave4IsDone(); +bool mpu_getLostArbitration(); +bool mpu_getSlave4Nack(); +bool mpu_getSlave3Nack(); +bool mpu_getSlave2Nack(); +bool mpu_getSlave1Nack(); +bool mpu_getSlave0Nack(); + +// INT_PIN_CFG register +bool mpu_getInterruptMode(); +void mpu_setInterruptMode(bool mode); +bool mpu_getInterruptDrive(); +void mpu_setInterruptDrive(bool drive); +bool mpu_getInterruptLatch(); +void mpu_setInterruptLatch(bool latch); +bool mpu_getInterruptLatchClear(); +void mpu_setInterruptLatchClear(bool clear); +bool mpu_getFSyncInterruptLevel(); +void mpu_setFSyncInterruptLevel(bool level); +bool mpu_getFSyncInterruptEnabled(); +void mpu_setFSyncInterruptEnabled(bool enabled); +bool mpu_getI2CBypassEnabled(); +void mpu_setI2CBypassEnabled(bool enabled); +bool mpu_getClockOutputEnabled(); +void mpu_setClockOutputEnabled(bool enabled); + +// INT_ENABLE register +uint8_t mpu_getIntEnabled(); +void mpu_setIntEnabled(uint8_t enabled); +bool mpu_getIntFreefallEnabled(); +void mpu_setIntFreefallEnabled(bool enabled); +bool mpu_getIntMotionEnabled(); +void mpu_setIntMotionEnabled(bool enabled); +bool mpu_getIntZeroMotionEnabled(); +void mpu_setIntZeroMotionEnabled(bool enabled); +bool mpu_getIntFIFOBufferOverflowEnabled(); +void mpu_setIntFIFOBufferOverflowEnabled(bool enabled); +bool mpu_getIntI2CMasterEnabled(); +void mpu_setIntI2CMasterEnabled(bool enabled); +bool mpu_getIntDataReadyEnabled(); +void mpu_setIntDataReadyEnabled(bool enabled); + +// INT_STATUS register +uint8_t mpu_getIntStatus(); +bool mpu_getIntFreefallStatus(); +bool mpu_getIntMotionStatus(); +bool mpu_getIntZeroMotionStatus(); +bool mpu_getIntFIFOBufferOverflowStatus(); +bool mpu_getIntI2CMasterStatus(); +bool mpu_getIntDataReadyStatus(); + +// ACCEL_*OUT_* registers +void mpu_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 mpu_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, + int16_t* gy, int16_t* gz); +void mpu_getAcceleration(int16_t* x, int16_t* y, int16_t* z); +// void mpu_getAcceleration(int32_t* x, int32_t* y, int32_t* z); +int16_t mpu_getAccelerationX(); +int16_t mpu_getAccelerationY(); +int16_t mpu_getAccelerationZ(); + +// TEMP_OUT_* registers +int16_t mpu_getTemperature(); + +// GYRO_*OUT_* registers +void mpu_getRotation(int16_t* x, int16_t* y, int16_t* z); +// void mpu_getRotation(int32_t* x, int32_t* y, int32_t* z); +int16_t mpu_getRotationX(); +int16_t mpu_getRotationY(); +int16_t mpu_getRotationZ(); + +// EXT_SENS_DATA_* registers +uint8_t mpu_getExternalSensorByte(int position); +uint16_t mpu_getExternalSensorWord(int position); +uint32_t getExternalSensorDWord(int position); + +// MOT_DETECT_STATUS register +bool mpu_getXNegMotionDetected(); +bool mpu_getXPosMotionDetected(); +bool mpu_getYNegMotionDetected(); +bool mpu_getYPosMotionDetected(); +bool mpu_getZNegMotionDetected(); +bool mpu_getZPosMotionDetected(); +bool mpu_getZeroMotionDetected(); + +// I2C_SLV*_DO register +void mpu_setSlaveOutputByte(uint8_t num, uint8_t data); + +// I2C_MST_DELAY_CTRL register +bool mpu_getExternalShadowDelayEnabled(); +void mpu_setExternalShadowDelayEnabled(bool enabled); +bool mpu_getSlaveDelayEnabled(uint8_t num); +void mpu_setSlaveDelayEnabled(uint8_t num, bool enabled); + +// SIGNAL_PATH_RESET register +void mpu_resetGyroscopePath(); +void mpu_resetAccelerometerPath(); +void mpu_resetTemperaturePath(); + +// MOT_DETECT_CTRL register +uint8_t mpu_getAccelerometerPowerOnDelay(); +void mpu_setAccelerometerPowerOnDelay(uint8_t delay); +uint8_t mpu_getFreefallDetectionCounterDecrement(); +void mpu_setFreefallDetectionCounterDecrement(uint8_t decrement); +uint8_t mpu_getMotionDetectionCounterDecrement(); +void mpu_setMotionDetectionCounterDecrement(uint8_t decrement); + +// USER_CTRL register +bool mpu_getFIFOEnabled(); +void mpu_setFIFOEnabled(bool enabled); +bool mpu_getI2CMasterModeEnabled(); +void mpu_setI2CMasterModeEnabled(bool enabled); +void mpu_switchSPIEnabled(bool enabled); +void mpu_resetFIFO(); +void mpu_resetI2CMaster(); +void mpu_resetSensors(); + +// PWR_MGMT_1 register +void mpu_reset(); +bool mpu_getSleepEnabled(); +void mpu_setSleepEnabled(bool enabled); +bool mpu_getWakeCycleEnabled(); +void mpu_setWakeCycleEnabled(bool enabled); +bool mpu_getTempSensorEnabled(); +void mpu_setTempSensorEnabled(bool enabled); +uint8_t mpu_getClockSource(); +void mpu_setClockSource(uint8_t source); + +// PWR_MGMT_2 register +uint8_t mpu_getWakeFrequency(); +void mpu_setWakeFrequency(uint8_t frequency); +bool mpu_getStandbyXAccelEnabled(); +void mpu_setStandbyXAccelEnabled(bool enabled); +bool mpu_getStandbyYAccelEnabled(); +void mpu_setStandbyYAccelEnabled(bool enabled); +bool mpu_getStandbyZAccelEnabled(); +void mpu_setStandbyZAccelEnabled(bool enabled); +bool mpu_getStandbyXGyroEnabled(); +void mpu_setStandbyXGyroEnabled(bool enabled); +bool mpu_getStandbyYGyroEnabled(); +void mpu_setStandbyYGyroEnabled(bool enabled); +bool mpu_getStandbyZGyroEnabled(); +void mpu_setStandbyZGyroEnabled(bool enabled); + +// FIFO_COUNT_* registers +uint16_t mpu_getFIFOCount(); + +// FIFO_R_W register +uint8_t mpu_getFIFOByte(); +void mpu_setFIFOByte(uint8_t data); +void mpu_getFIFOBytes(uint8_t* data, uint8_t length); + +// WHO_AM_I register +uint8_t mpu_getDeviceID(); +void mpu_setDeviceID(uint8_t id); + +// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== + +// XG_OFFS_TC register +uint8_t mpu_getOTPBankValid(); +void mpu_setOTPBankValid(bool enabled); +int8_t getXGyroOffsetTC(); +void mpu_setXGyroOffsetTC(int8_t offset); + +// YG_OFFS_TC register +int8_t getYGyroOffsetTC(); +void mpu_setYGyroOffsetTC(int8_t offset); + +// ZG_OFFS_TC register +int8_t getZGyroOffsetTC(); +void mpu_setZGyroOffsetTC(int8_t offset); + +// X_FINE_GAIN register +int8_t getXFineGain(); +void mpu_setXFineGain(int8_t gain); + +// Y_FINE_GAIN register +int8_t getYFineGain(); +void mpu_setYFineGain(int8_t gain); + +// Z_FINE_GAIN register +int8_t getZFineGain(); +void mpu_setZFineGain(int8_t gain); + +// XA_OFFS_* registers +int16_t mpu_getXAccelOffset(); +void mpu_setXAccelOffset(int16_t offset); + +// YA_OFFS_* register +int16_t mpu_getYAccelOffset(); +void mpu_setYAccelOffset(int16_t offset); + +// ZA_OFFS_* register +int16_t mpu_getZAccelOffset(); +void mpu_setZAccelOffset(int16_t offset); + +// XG_OFFS_USR* registers +int16_t mpu_getXGyroOffset(); +void mpu_setXGyroOffset(int16_t offset); + +// YG_OFFS_USR* register +int16_t mpu_getYGyroOffset(); +void mpu_setYGyroOffset(int16_t offset); + +// ZG_OFFS_USR* register +int16_t mpu_getZGyroOffset(); +void mpu_setZGyroOffset(int16_t offset); + +// INT_ENABLE register (DMP functions) +bool mpu_getIntPLLReadyEnabled(); +void mpu_setIntPLLReadyEnabled(bool enabled); +bool mpu_getIntDMPEnabled(); +void mpu_setIntDMPEnabled(bool enabled); + +// DMP_INT_STATUS +bool mpu_getDMPInt5Status(); +bool mpu_getDMPInt4Status(); +bool mpu_getDMPInt3Status(); +bool mpu_getDMPInt2Status(); +bool mpu_getDMPInt1Status(); +bool mpu_getDMPInt0Status(); + +// INT_STATUS register (DMP functions) +bool mpu_getIntPLLReadyStatus(); +bool mpu_getIntDMPStatus(); + +// USER_CTRL register (DMP functions) +bool mpu_getDMPEnabled(); +void mpu_setDMPEnabled(bool enabled); +void mpu_resetDMP(); + +// BANK_SEL register +void mpu_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank); + +// MEM_START_ADDR register +void mpu_setMemoryStartAddress(uint8_t address); + +// MEM_R_W register +uint8_t mpu_readMemoryByte(); +void mpu_writeMemoryByte(uint8_t data); +void mpu_readMemoryBlock( + uint8_t* data, uint16_t dataSize, uint8_t bank, uint8_t address); +void mpu_writeMemoryBlock(const uint8_t* data, uint16_t dataSize, + uint8_t bank = 0, uint8_t address = 0); + +//bool mpu_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem); +//bool mpu_writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize); + +// DMP_CFG_1 register +uint8_t mpu_getDMPConfig1(); +void mpu_setDMPConfig1(uint8_t config); + +// DMP_CFG_2 register +uint8_t mpu_getDMPConfig2(); +void mpu_setDMPConfig2(uint8_t config); + +#endif /* _mpu_H_ */ diff --git a/fw/rbcx-coprocessor/include/utils/Debug.hpp b/fw/rbcx-coprocessor/include/utils/Debug.hpp index 5a014951..fdbf1853 100644 --- a/fw/rbcx-coprocessor/include/utils/Debug.hpp +++ b/fw/rbcx-coprocessor/include/utils/Debug.hpp @@ -58,7 +58,7 @@ inline void printTaskInfo() { unsigned bytesFree = status.usStackHighWaterMark * sizeof(StackType_t); - printf("#%d %s: %u bytes untouched (of %u)\n", status.xTaskNumber, + printf("#%lu %s: %u bytes untouched (of %u)\n", status.xTaskNumber, status.pcTaskName, bytesFree, bytesTotal); } } diff --git a/fw/rbcx-coprocessor/include/utils/SemaphoreWrapper.hpp b/fw/rbcx-coprocessor/include/utils/SemaphoreWrapper.hpp new file mode 100644 index 00000000..76771ccc --- /dev/null +++ b/fw/rbcx-coprocessor/include/utils/SemaphoreWrapper.hpp @@ -0,0 +1,40 @@ +#pragma once + +#include "FreeRTOS.h" +#include "semphr.h" + +class BinarySemaphoreWrapper { +public: + BinarySemaphoreWrapper() + : m_handle(nullptr) {} + + ~BinarySemaphoreWrapper() { + if (m_handle) + vSemaphoreDelete(m_handle); + } + + void create() { + if (m_handle) + abort(); + + m_handle = xSemaphoreCreateBinaryStatic(&m_buffer); + } + + SemaphoreHandle_t native_handle() const { return m_handle; } + + bool take(TickType_t timeout = portMAX_DELAY) { + return xSemaphoreTake(m_handle, timeout) == pdTRUE; + } + + void give() { xSemaphoreGive(m_handle); } + + void giveFromIsr() { + BaseType_t woken = 0; + xSemaphoreGiveFromISR(m_handle, &woken); + portYIELD_FROM_ISR(woken); + } + +private: + SemaphoreHandle_t m_handle; + StaticSemaphore_t m_buffer; +}; diff --git a/fw/rbcx-coprocessor/include/utils/TaskWrapper.hpp b/fw/rbcx-coprocessor/include/utils/TaskWrapper.hpp index 4c975b8f..a3b7efe8 100644 --- a/fw/rbcx-coprocessor/include/utils/TaskWrapper.hpp +++ b/fw/rbcx-coprocessor/include/utils/TaskWrapper.hpp @@ -25,6 +25,21 @@ template class TaskWrapper { TaskHandle_t handle() const { return m_handle; } + void onTaskEnd() { +#ifndef NDEBUG + if(m_handle != xTaskGetCurrentTaskHandle()) { + DEBUG("on_task_end was called from different task!\n"); + abort(); + } +#endif + + if (!m_handle) + return; + + vTaskDelete(nullptr); + m_handle = nullptr; + } + private: TaskWrapper(const TaskWrapper&) = delete; diff --git a/fw/rbcx-coprocessor/platformio.ini b/fw/rbcx-coprocessor/platformio.ini index 0d18ed4b..b73856ef 100644 --- a/fw/rbcx-coprocessor/platformio.ini +++ b/fw/rbcx-coprocessor/platformio.ini @@ -16,7 +16,7 @@ platform = https://github.com/platformio/platform-ststm32/archive/refs/tags/v7.0 board = genericSTM32F103VC framework = stm32cube lib_deps = - https://github.com/RoboticsBrno/RB3204-RBCX-coproc-comm/archive/1ed2bbc8fda0b9b1c6592f5f39bd9bbb1213d569.zip + https://github.com/RoboticsBrno/RB3204-RBCX-coproc-comm/archive/77f4ada13fb3b348cca408ac8f614597e61c370c.zip build_flags = -Iinclude diff --git a/fw/rbcx-coprocessor/src/Bsp.cpp b/fw/rbcx-coprocessor/src/Bsp.cpp index ddead44e..634865bb 100644 --- a/fw/rbcx-coprocessor/src/Bsp.cpp +++ b/fw/rbcx-coprocessor/src/Bsp.cpp @@ -10,6 +10,7 @@ #include "UltrasoundController.hpp" #include "utils/Debug.hpp" #include "utils/TaskWrapper.hpp" +#include "MpuController.hpp" static TaskWrapper<1024> softResetTask; @@ -29,6 +30,13 @@ extern "C" void EXTI9_5_IRQHandler(void) { | uts3EchoPin.second | uts4EchoPin.second); } +extern "C" void EXTI15_10_IRQHandler(void) { + // This EXTI vector only serves MPU interrupt pin + + mpuOnIntTriggered(); + __HAL_GPIO_EXTI_CLEAR_IT(mpuIntPin.second); +} + void softResetInit() { softResetTask.start("softrst", softResetTaskPrio, []() { while (true) { diff --git a/fw/rbcx-coprocessor/src/DebugLink.cpp b/fw/rbcx-coprocessor/src/DebugLink.cpp index 9d9ccea3..4d8f4a54 100644 --- a/fw/rbcx-coprocessor/src/DebugLink.cpp +++ b/fw/rbcx-coprocessor/src/DebugLink.cpp @@ -14,9 +14,9 @@ #include "BuzzerController.hpp" #include "Dispatcher.hpp" #include "I2cController.hpp" -#include "Mpu6050.hpp" #include "OledController.hpp" #include "MpuController.hpp" +#include "MpuDriver.hpp" #include "Power.hpp" #include "UsbCdcLink.h" #include "coproc_codec.h" diff --git a/fw/rbcx-coprocessor/src/I2cController.cpp b/fw/rbcx-coprocessor/src/I2cController.cpp index 71da5912..6250438a 100644 --- a/fw/rbcx-coprocessor/src/I2cController.cpp +++ b/fw/rbcx-coprocessor/src/I2cController.cpp @@ -35,30 +35,37 @@ THE SOFTWARE. #include "OledController.hpp" #include "utils/Debug.hpp" +#include "timers.h" #include "utils/MutexWrapper.hpp" #include "utils/QueueWrapper.hpp" +#include "utils/SemaphoreWrapper.hpp" #include "utils/TaskWrapper.hpp" -#include "timers.h" // #include "event_groups.h" #include static TaskWrapper<1024> i2cTask; -TaskHandle_t i2cTaskHandle; static QueueWrapper i2cQueue; -static xTaskHandle i2cCallingTask; static MutexWrapper i2cMutex; - -EventGroupHandle_t i2cEventGroup; -static StaticEventGroup_t i2cEventBuffer; +static BinarySemaphoreWrapper i2cTxSemaphore; // Hold pointer to inited HAL I2C device I2C_HandleTypeDef I2Cdev_hi2c; +void i2cSetEventFlag(I2cEvents flag) { + xTaskNotify(i2cTask.handle(), flag, eSetBits); +} + +void i2cSetEventFlagFromIsr(I2cEvents flag) { + BaseType_t woken = 0; + xTaskNotifyFromISR(i2cTask.handle(), flag, eSetBits, &woken); + portYIELD_FROM_ISR(woken); +} + void i2cDispatch(const CoprocReq_I2cReq& req) { if (i2cQueue.push_back(req, 0)) { - xEventGroupSetBits(i2cEventGroup, I2C_MESSAGE); + i2cSetEventFlag(I2C_MESSAGE); } else { DEBUG("I2c queue overflow\n"); } @@ -84,80 +91,74 @@ uint8_t I2Cdev_init() { if (init == HAL_OK) { i2cQueue.create(); i2cMutex.create(); - i2cEventGroup = xEventGroupCreateStatic(&i2cEventBuffer); + i2cTxSemaphore.create(); i2cTask.start("i2c", i2cPrio, []() { - while (true) { - CoprocReq_I2cReq req; + CoprocReq_I2cReq req; + EventBits_t eventsBit = I2C_NONE; - EventBits_t eventsBit = I2C_NONE; - eventsBit = xEventGroupWaitBits( - i2cEventGroup, 0xFF, pdTRUE, 0, portMAX_DELAY); + while (true) { + if (xTaskNotifyWait(0, 0xFFFFFFFF, &eventsBit, portMAX_DELAY) + == pdFAIL) { + continue; + } if (eventsBit & I2C_MPU_TICK) { mpuTick(); - // DEBUG("SEND MPU\n"); } - while (i2cQueue.pop_front(req, 0)) { - switch (req.which_payload) { - case CoprocReq_I2cReq_oledReq_tag: - oledDispatch(req.payload.oledReq); - break; - case CoprocReq_I2cReq_mpuReq_tag: - mpuDispatch(req.payload.mpuReq); - // DEBUGLN("MPU Req %d", req.payload.mpuReq.which_mpuCmd); - break; + if (eventsBit & I2C_MESSAGE) { + while (i2cQueue.pop_front(req, 0)) { + switch (req.which_payload) { + case CoprocReq_I2cReq_oledReq_tag: + oledDispatch(req.payload.oledReq); + break; + case CoprocReq_I2cReq_mpuReq_tag: + mpuDispatch(req.payload.mpuReq); + // DEBUGLN("MPU Req %d", req.payload.mpuReq.which_mpuCmd); + break; + } } } // vTaskDelay(pdMS_TO_TICKS(10)); } }); - i2cTaskHandle = i2cTask.handle(); } else { DEBUG("Error I2c Init\n"); } } -void i2cNotify() { - BaseType_t woken = 0; - xTaskNotifyFromISR(i2cCallingTask, 0, eNoAction, &woken); - portYIELD_FROM_ISR(woken); -} - extern "C" void I2C1_EV_IRQHandler() { HAL_I2C_EV_IRQHandler(&I2Cdev_hi2c); } extern "C" void I2C1_ER_IRQHandler() { HAL_I2C_ER_IRQHandler(&I2Cdev_hi2c); } extern "C" __weak void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef* hi2c) { - i2cNotify(); + i2cTxSemaphore.giveFromIsr(); } extern "C" __weak void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef* hi2c) { - i2cNotify(); + i2cTxSemaphore.giveFromIsr(); } extern "C" __weak void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef* hi2c) { - i2cNotify(); + i2cTxSemaphore.giveFromIsr(); } extern "C" __weak void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef* hi2c) { - i2cNotify(); + i2cTxSemaphore.giveFromIsr(); } extern "C" __weak void HAL_I2C_ErrorCallback(I2C_HandleTypeDef* hi2c) { - i2cNotify(); + i2cTxSemaphore.giveFromIsr(); } -uint8_t i2cWait(HAL_StatusTypeDef beginStatus, uint32_t tout) {} - template uint8_t i2cWrap(F fun, uint32_t Timeout) { - uint16_t tout = Timeout > 0 ? Timeout : I2CDEV_DEFAULT_READ_TIMEOUT; std::scoped_lock lock(i2cMutex); - i2cCallingTask = xTaskGetCurrentTaskHandle(); - auto beginStatus = fun(); + uint16_t tout = Timeout > 0 ? Timeout : I2CDEV_DEFAULT_READ_TIMEOUT; + + auto beginStatus = fun(); if (beginStatus == HAL_OK) { - auto ok = xTaskNotifyWait(0, ~0, nullptr, pdMS_TO_TICKS(tout)); + auto ok = i2cTxSemaphore.take(pdMS_TO_TICKS(tout)); if (!ok) { DEBUG("I2C timeout\n"); @@ -170,9 +171,7 @@ template uint8_t i2cWrap(F fun, uint32_t Timeout) { } } -void i2cReset() { - i2cQueue.reset(); -} +void i2cReset() { i2cQueue.reset(); } /* Rewrited original functions */ uint8_t I2Cdev_Master_Transmit( @@ -183,7 +182,9 @@ uint8_t I2Cdev_Master_Transmit( &I2Cdev_hi2c, DevAddress << 1, pData, Size); if (beginStatus != HAL_OK) { - DEBUG("I2C ERR - Tx %d bytes, ret: %d\n", Size, beginStatus); + DEBUG("I2C ERR - Tx %d bytes, ret: %d %d %d\n", Size, + beginStatus, HAL_I2C_GetError(&I2Cdev_hi2c), + HAL_I2C_GetState(&I2Cdev_hi2c)); } return beginStatus; }, @@ -198,7 +199,9 @@ uint8_t I2Cdev_Master_Receive( &I2Cdev_hi2c, DevAddress << 1, pData, Size); if (beginStatus != HAL_OK) { - DEBUG("I2C ERR - Rx %d bytes, ret: %d\n", Size, beginStatus); + DEBUG("I2C ERR - Rx %d bytes, ret: %d %d %d\n", Size, + beginStatus, HAL_I2C_GetError(&I2Cdev_hi2c), + HAL_I2C_GetState(&I2Cdev_hi2c)); } return beginStatus; }, @@ -213,7 +216,8 @@ uint8_t I2Cdev_Mem_Write(uint16_t DevAddress, uint16_t MemAddress, DevAddress << 1, MemAddress, MemAddSize, pData, Size); if (beginStatus != HAL_OK) { - DEBUG("I2C ERR - Mem write %d bytes, ret: %d\n", Size, beginStatus); + DEBUG("I2C ERR - Mem write %d bytes, ret: %d\n", Size, + beginStatus); } return beginStatus; }, @@ -228,7 +232,8 @@ uint8_t I2Cdev_Mem_Read(uint16_t DevAddress, uint16_t MemAddress, DevAddress << 1, MemAddress, MemAddSize, pData, Size); if (beginStatus != HAL_OK) { - DEBUG("I2C ERR - Mem read %d bytes, ret: %d\n", Size, beginStatus); + DEBUG("I2C ERR - Mem read %d bytes, ret: %d\n", Size, + beginStatus); } return beginStatus; }, @@ -544,7 +549,7 @@ uint16_t I2Cdev_writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) { * @return Status of operation (true = success) */ uint16_t I2Cdev_writeBytes( - uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* pData) { + uint8_t devAddr, uint8_t regAddr, uint8_t length, const uint8_t* pData) { // Creating array to store regAddr + data in one buffer uint8_t buffer[length + 1]; buffer[0] = regAddr; @@ -564,7 +569,7 @@ uint16_t I2Cdev_writeBytes( * @return Status of operation (true = success) */ uint16_t I2Cdev_writeWords( - uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data) { + uint8_t devAddr, uint8_t regAddr, uint8_t length, const uint16_t* data) { // Creating array to store regAddr + data in one buffer uint8_t buffer[length + 1]; buffer[0] = regAddr; diff --git a/fw/rbcx-coprocessor/src/MpuController.cpp b/fw/rbcx-coprocessor/src/MpuController.cpp index d851b6a9..d7a4922a 100644 --- a/fw/rbcx-coprocessor/src/MpuController.cpp +++ b/fw/rbcx-coprocessor/src/MpuController.cpp @@ -1,3540 +1,439 @@ -// I2Cdev library collection - mpu 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 -// 2017-03-28 - tested basic function on STM32 - -// 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 "MpuController.hpp" -#include "Dispatcher.hpp" -#include "utils/TickTimer.hpp" - -#include "Bsp.hpp" - -#include "utils/QueueWrapper.hpp" -#include "utils/TaskWrapper.hpp" - -#include "FreeRTOS.h" -#include "timers.h" - -#include "event_groups.h" - -typedef struct MpuVector { - int16_t x; - int16_t y; - int16_t z; -} MpuVector; - -typedef struct MpuVector32 { - int32_t x; - int32_t y; - int32_t z; -} MpuVector32; - -typedef struct MpuMotion6 { - MpuVector accel; - MpuVector gyro; -} MpuMotion6; - -typedef struct MpuMotion32 { - MpuVector32 accel; - MpuVector32 gyro; -} MpuMotion32; - -static mpu_t mpu6050; -static MpuMotion32 mpuAggrData; - -static constexpr uint32_t mpuTickPeriodMs = 10; -static uint32_t mpuAggrCounter = 0; -static TimerHandle_t mpuTimerHandle; -static StaticTimer_t mpuTimerBuffer; -static uint16_t compressCoef = 4; -static void mpuTickCallback(TimerHandle_t tim) { - xEventGroupSetBits(i2cEventGroup, I2C_MPU_TICK); -} - -static void mpuRead(MpuMotion6& data) { - mpu_getMotion6(&data.accel.x, &data.accel.y, &data.accel.z, &data.gyro.x, - &data.gyro.y, &data.gyro.z); -} - -static void mpuSend(const MpuMotion32& data) { - // DEBUG( - // "DEBUG MPU SEND [%d] acc: x:%d; y:%d; z:%d | gyro: x:%d; y:%d; z:%d\n", - // mpuAggrCounter, data.accel.x, data.accel.y, data.accel.z, data.gyro.x, - // data.gyro.y, data.gyro.z); - - CoprocStat status = { - .which_payload = CoprocStat_mpuStat_tag, - }; - - status.payload.mpuStat.accel.x = data.accel.x; - status.payload.mpuStat.accel.y = data.accel.y; - status.payload.mpuStat.accel.z = data.accel.z; - status.payload.mpuStat.has_accel = true; - - status.payload.mpuStat.gyro.x = data.gyro.x; - status.payload.mpuStat.gyro.y = data.gyro.y; - status.payload.mpuStat.gyro.z = data.gyro.z; - status.payload.mpuStat.has_gyro = true; - status.payload.mpuStat.compressCoef = compressCoef; - dispatcherEnqueueStatus(status); -} - -void mpuDispatch(const CoprocReq_MpuReq& req) { - switch (req.which_mpuCmd) { - case CoprocReq_MpuReq_init_tag: - mpuInitialize(); - break; - case CoprocReq_MpuReq_oneSend_tag: - MpuMotion6 data; - MpuMotion32 data32; - mpuRead(data); - data32.accel.x = data.accel.x; - data32.accel.y = data.accel.y; - data32.accel.z = data.accel.z; - data32.gyro.x = data.gyro.x; - data32.gyro.y = data.gyro.y; - data32.gyro.z = data.gyro.z; - mpuSend(data32); - break; - case CoprocReq_MpuReq_startSend_tag: { - if (xTimerStart(mpuTimerHandle, 0) == pdFALSE) { - DEBUG("MPU6050 timer start failure\n"); - } - mpuAggrCounter = 0; - break; - } - - case CoprocReq_MpuReq_stopSend_tag: { - if (xTimerStop(mpuTimerHandle, 0) == pdFALSE) { - DEBUG("MPU6050 timer stop failure\n"); - } - break; - } - - case CoprocReq_MpuReq_setCompressCoef_tag: { - uint16_t coef = req.mpuCmd.setCompressCoef; - if (coef > 0 && coef <= 20) { - compressCoef = coef; - DEBUGLN("MPU6050 set new compression coef: %d", compressCoef); - } - break; - } - - case CoprocReq_MpuReq_getCompressCoef_tag: { - CoprocStat status = { - .which_payload = CoprocStat_mpuStat_tag, - .payload = { - .mpuStat = { - .compressCoef = compressCoef, - }, - }, - }; - dispatcherEnqueueStatus(status); - break; - } - }; -} - -void mpuTick() { - MpuMotion6 data; - mpuRead(data); - // DEBUG("MPU6050 [%d] acc: x:%d; y:%d; z:%d | gyro: x:%d; y:%d; z:%d\n", - // mpuAggrCounter, data.accel.x, data.accel.y, data.accel.z, data.gyro.x, - // data.gyro.y, data.gyro.z); - - mpuAggrData.accel.x += data.accel.x; - mpuAggrData.accel.y += data.accel.y; - mpuAggrData.accel.z += data.accel.z; - mpuAggrData.gyro.x += data.gyro.x; - mpuAggrData.gyro.y += data.gyro.y; - mpuAggrData.gyro.z += data.gyro.z; - - mpuAggrCounter++; - if (mpuAggrCounter >= compressCoef) { - mpuSend(mpuAggrData); - - mpuAggrData.accel.x = 0; - mpuAggrData.accel.y = 0; - mpuAggrData.accel.z = 0; - mpuAggrData.gyro.x = 0; - mpuAggrData.gyro.y = 0; - mpuAggrData.gyro.z = 0; - mpuAggrCounter = 0; - } -} - -void mpuCreate() { - mpu6050.devAddr = mpu_ADDRESS_AD0_HIGH; - mpuTimerHandle - = xTimerCreateStatic("mpuTimer", pdMS_TO_TICKS(mpuTickPeriodMs), true, - nullptr, mpuTickCallback, &mpuTimerBuffer); -} - -/** 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 mpuInitialize() { - mpuReset(); - - if (mpu_testConnection()) { - mpu_setClockSource(mpu_CLOCK_PLL_XGYRO); - mpu_setFullScaleGyroRange(mpu_GYRO_FS_250); - mpu_setFullScaleAccelRange(mpu_ACCEL_FS_2); - mpu_setSleepEnabled(false); - } else { - DEBUG("MPU6050 is not connected\n"); - CoprocStat status = { - .which_payload = CoprocStat_faultStat_tag, - .payload = { - .faultStat = { - .which_fault = CoprocStat_FaultStat_mpuFault_tag, - }, - }, - }; - dispatcherEnqueueStatus(status); - } -} - -void mpuReset() { - if (xTimerStop(mpuTimerHandle, 0) == pdFALSE) { - DEBUG("Time queue overflow\n"); - } -} - -/** Verify the I2C connection. - * Make sure the device is connected and responds as expected. - * @return True if connection is valid, false otherwise - */ -bool mpu_testConnection() { return mpu_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 mpu_getAuxVDDIOLevel() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_PWR_MODE_BIT, - mpu6050.buffer, 0); - 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 mpu_setAuxVDDIOLevel(uint8_t level) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_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 mpu_RA_SMPLRT_DIV - */ -uint8_t mpu_getRate() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_SMPLRT_DIV, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set gyroscope sample rate divider. - * @param rate New sample rate divider - * @see getRate() - * @see mpu_RA_SMPLRT_DIV - */ -void mpu_setRate(uint8_t rate) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_getExternalFrameSync() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_EXT_SYNC_SET_BIT, - mpu_CFG_EXT_SYNC_SET_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set external FSYNC configuration. - * @see getExternalFrameSync() - * @see mpu_RA_CONFIG - * @param sync New FSYNC configuration value - */ -void mpu_setExternalFrameSync(uint8_t sync) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_EXT_SYNC_SET_BIT, - mpu_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 mpu_RA_CONFIG - * @see mpu_CFG_DLPF_CFG_BIT - * @see mpu_CFG_DLPF_CFG_LENGTH - */ -uint8_t mpu_getDLPFMode() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_DLPF_CFG_BIT, - mpu_CFG_DLPF_CFG_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set digital low-pass filter configuration. - * @param mode New DLFP configuration setting - * @see getDLPFBandwidth() - * @see mpu_DLPF_BW_256 - * @see mpu_RA_CONFIG - * @see mpu_CFG_DLPF_CFG_BIT - * @see mpu_CFG_DLPF_CFG_LENGTH - */ -void mpu_setDLPFMode(uint8_t mode) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_DLPF_CFG_BIT, - mpu_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 mpu_GYRO_FS_250 - * @see mpu_RA_GYRO_CONFIG - * @see mpu_GCONFIG_FS_SEL_BIT - * @see mpu_GCONFIG_FS_SEL_LENGTH - */ -uint8_t mpu_getFullScaleGyroRange() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_GYRO_CONFIG, mpu_GCONFIG_FS_SEL_BIT, - mpu_GCONFIG_FS_SEL_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set full-scale gyroscope range. - * @param range New full-scale gyroscope range value - * @see getFullScaleRange() - * @see mpu_GYRO_FS_250 - * @see mpu_RA_GYRO_CONFIG - * @see mpu_GCONFIG_FS_SEL_BIT - * @see mpu_GCONFIG_FS_SEL_LENGTH - */ -void mpu_setFullScaleGyroRange(uint8_t range) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_GYRO_CONFIG, - mpu_GCONFIG_FS_SEL_BIT, mpu_GCONFIG_FS_SEL_LENGTH, range); -} - -// ACCEL_CONFIG register - -/** Get self-test enabled setting for accelerometer X axis. - * @return Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -bool mpu_getAccelXSelfTest() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_XA_ST_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get self-test enabled setting for accelerometer X axis. - * @param enabled Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -void mpu_setAccelXSelfTest(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_XA_ST_BIT, enabled); -} -/** Get self-test enabled value for accelerometer Y axis. - * @return Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -bool mpu_getAccelYSelfTest() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_YA_ST_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get self-test enabled value for accelerometer Y axis. - * @param enabled Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -void mpu_setAccelYSelfTest(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_YA_ST_BIT, enabled); -} -/** Get self-test enabled value for accelerometer Z axis. - * @return Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -bool mpu_getAccelZSelfTest() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_ZA_ST_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set self-test enabled value for accelerometer Z axis. - * @param enabled Self-test enabled value - * @see mpu_RA_ACCEL_CONFIG - */ -void mpu_setAccelZSelfTest(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_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 mpu_ACCEL_FS_2 - * @see mpu_RA_ACCEL_CONFIG - * @see mpu_ACONFIG_AFS_SEL_BIT - * @see mpu_ACONFIG_AFS_SEL_LENGTH - */ -uint8_t mpu_getFullScaleAccelRange() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, - mpu_ACONFIG_AFS_SEL_BIT, mpu_ACONFIG_AFS_SEL_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set full-scale accelerometer range. - * @param range New full-scale accelerometer range setting - * @see getFullScaleAccelRange() - */ -void mpu_setFullScaleAccelRange(uint8_t range) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, - mpu_ACONFIG_AFS_SEL_BIT, mpu_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 mpu_DHPF_RESET - * @see mpu_RA_ACCEL_CONFIG - */ -uint8_t mpu_getDHPFMode() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, - mpu_ACONFIG_ACCEL_HPF_BIT, mpu_ACONFIG_ACCEL_HPF_LENGTH, mpu6050.buffer, - 0); - return mpu6050.buffer[0]; -} -/** Set the high-pass filter configuration. - * @param bandwidth New high-pass filter configuration - * @see setDHPFMode() - * @see mpu_DHPF_RESET - * @see mpu_RA_ACCEL_CONFIG - */ -void mpu_setDHPFMode(uint8_t bandwidth) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, - mpu_ACONFIG_ACCEL_HPF_BIT, mpu_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 mpu_RA_FF_THR - */ -uint8_t mpu_getFreefallDetectionThreshold() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FF_THR, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get free-fall event acceleration threshold. - * @param threshold New free-fall acceleration threshold value (LSB = 2mg) - * @see getFreefallDetectionThreshold() - * @see mpu_RA_FF_THR - */ -void mpu_setFreefallDetectionThreshold(uint8_t threshold) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_FF_DUR - */ -uint8_t mpu_getFreefallDetectionDuration() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FF_DUR, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get free-fall event duration threshold. - * @param duration New free-fall duration threshold value (LSB = 1ms) - * @see getFreefallDetectionDuration() - * @see mpu_RA_FF_DUR - */ -void mpu_setFreefallDetectionDuration(uint8_t duration) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_MOT_THR - */ -uint8_t mpu_getMotionDetectionThreshold() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MOT_THR, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set free-fall event acceleration threshold. - * @param threshold New motion detection acceleration threshold value (LSB = 2mg) - * @see getMotionDetectionThreshold() - * @see mpu_RA_MOT_THR - */ -void mpu_setMotionDetectionThreshold(uint8_t threshold) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_MOT_DUR - */ -uint8_t mpu_getMotionDetectionDuration() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MOT_DUR, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set motion detection event duration threshold. - * @param duration New motion detection duration threshold value (LSB = 1ms) - * @see getMotionDetectionDuration() - * @see mpu_RA_MOT_DUR - */ -void mpu_setMotionDetectionDuration(uint8_t duration) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_ZRMOT_THR - */ -uint8_t mpu_getZeroMotionDetectionThreshold() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_ZRMOT_THR, mpu6050.buffer, 0); - 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 mpu_RA_ZRMOT_THR - */ -void mpu_setZeroMotionDetectionThreshold(uint8_t threshold) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_ZRMOT_DUR - */ -uint8_t mpu_getZeroMotionDetectionDuration() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_ZRMOT_DUR, mpu6050.buffer, 0); - 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 mpu_RA_ZRMOT_DUR - */ -void mpu_setZeroMotionDetectionDuration(uint8_t duration) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getTempFIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_TEMP_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set temperature FIFO enabled value. - * @param enabled New temperature FIFO enabled value - * @see getTempFIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setTempFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getXGyroFIFOEnabled() { - I2Cdev_readBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_XG_FIFO_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set gyroscope X-axis FIFO enabled value. - * @param enabled New gyroscope X-axis FIFO enabled value - * @see getXGyroFIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setXGyroFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getYGyroFIFOEnabled() { - I2Cdev_readBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_YG_FIFO_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set gyroscope Y-axis FIFO enabled value. - * @param enabled New gyroscope Y-axis FIFO enabled value - * @see getYGyroFIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setYGyroFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getZGyroFIFOEnabled() { - I2Cdev_readBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_ZG_FIFO_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set gyroscope Z-axis FIFO enabled value. - * @param enabled New gyroscope Z-axis FIFO enabled value - * @see getZGyroFIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setZGyroFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getAccelFIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_ACCEL_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set accelerometer FIFO enabled value. - * @param enabled New accelerometer FIFO enabled value - * @see getAccelFIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setAccelFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getSlave2FIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV2_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Slave 2 FIFO enabled value. - * @param enabled New Slave 2 FIFO enabled value - * @see getSlave2FIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setSlave2FIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getSlave1FIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV1_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Slave 1 FIFO enabled value. - * @param enabled New Slave 1 FIFO enabled value - * @see getSlave1FIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setSlave1FIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN - */ -bool mpu_getSlave0FIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV0_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Slave 0 FIFO enabled value. - * @param enabled New Slave 0 FIFO enabled value - * @see getSlave0FIFOEnabled() - * @see mpu_RA_FIFO_EN - */ -void mpu_setSlave0FIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_I2C_MST_CTRL - */ -bool mpu_getMultiMasterEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_MULT_MST_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set multi-master enabled value. - * @param enabled New multi-master enabled value - * @see getMultiMasterEnabled() - * @see mpu_RA_I2C_MST_CTRL - */ -void mpu_setMultiMasterEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL - */ -bool mpu_getWaitForExternalSensorEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_WAIT_FOR_ES_BIT, - mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_CTRL - */ -void mpu_setWaitForExternalSensorEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_MST_CTRL - */ -bool mpu_getSlave3FIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_SLV_3_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Slave 3 FIFO enabled value. - * @param enabled New Slave 3 FIFO enabled value - * @see getSlave3FIFOEnabled() - * @see mpu_RA_MST_CTRL - */ -void mpu_setSlave3FIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL - */ -bool mpu_getSlaveReadWriteTransitionEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_P_NSR_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set slave read/write transition enabled value. - * @param enabled New slave read/write transition enabled value - * @see getSlaveReadWriteTransitionEnabled() - * @see mpu_RA_I2C_MST_CTRL - */ -void mpu_setSlaveReadWriteTransitionEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL - */ -uint8_t mpu_getMasterClockSpeed() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_CLK_BIT, - mpu_I2C_MST_CLK_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set I2C master clock speed. - * @reparam speed Current I2C master clock speed - * @see mpu_RA_I2C_MST_CTRL - */ -void mpu_setMasterClockSpeed(uint8_t speed) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_CLK_BIT, - mpu_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 mpu_RA_I2C_SLV0_ADDR - */ -uint8_t mpu_getSlaveAddress(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readByte( - mpu6050.devAddr, mpu_RA_I2C_SLV0_ADDR + num * 3, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_ADDR - */ -void mpu_setSlaveAddress(uint8_t num, uint8_t address) { - if (num > 3) - return; - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV0_REG - */ -uint8_t mpu_getSlaveRegister(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readByte( - mpu6050.devAddr, mpu_RA_I2C_SLV0_REG + num * 3, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_REG - */ -void mpu_setSlaveRegister(uint8_t num, uint8_t reg) { - if (num > 3) - return; - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV0_CTRL - */ -bool mpu_getSlaveEnabled(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_EN_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_CTRL - */ -void mpu_setSlaveEnabled(uint8_t num, bool enabled) { - if (num > 3) - return; - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_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 mpu_RA_I2C_SLV0_CTRL - */ -bool mpu_getSlaveWordByteSwap(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_BYTE_SW_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_CTRL - */ -void mpu_setSlaveWordByteSwap(uint8_t num, bool enabled) { - if (num > 3) - return; - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_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 mpu_RA_I2C_SLV0_CTRL - */ -bool mpu_getSlaveWriteMode(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_REG_DIS_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_CTRL - */ -void mpu_setSlaveWriteMode(uint8_t num, bool mode) { - if (num > 3) - return; - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_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 mpu_RA_I2C_SLV0_CTRL - */ -bool mpu_getSlaveWordGroupOffset(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_GRP_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_CTRL - */ -void mpu_setSlaveWordGroupOffset(uint8_t num, bool enabled) { - if (num > 3) - return; - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_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 mpu_RA_I2C_SLV0_CTRL - */ -uint8_t mpu_getSlaveDataLength(uint8_t num) { - if (num > 3) - return 0; - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_LEN_BIT, mpu_I2C_SLV_LEN_LENGTH, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_CTRL - */ -void mpu_setSlaveDataLength(uint8_t num, uint8_t length) { - if (num > 3) - return; - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, - mpu_I2C_SLV_LEN_BIT, mpu_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 mpu_RA_I2C_SLV4_ADDR - */ -uint8_t mpu_getSlave4Address() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_ADDR, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set the I2C address of Slave 4. - * @param address New address for Slave 4 - * @see getSlave4Address() - * @see mpu_RA_I2C_SLV4_ADDR - */ -void mpu_setSlave4Address(uint8_t address) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_REG - */ -uint8_t mpu_getSlave4Register() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_REG, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set the active internal register for Slave 4. - * @param reg New active register for Slave 4 - * @see getSlave4Register() - * @see mpu_RA_I2C_SLV4_REG - */ -void mpu_setSlave4Register(uint8_t reg) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_DO - */ -void mpu_setSlave4OutputByte(uint8_t data) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_CTRL - */ -bool mpu_getSlave4Enabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_I2C_SLV4_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set the enabled value for Slave 4. - * @param enabled New enabled value for Slave 4 - * @see getSlave4Enabled() - * @see mpu_RA_I2C_SLV4_CTRL - */ -void mpu_setSlave4Enabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_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 mpu_RA_I2C_SLV4_CTRL - */ -bool mpu_getSlave4InterruptEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, - mpu_I2C_SLV4_INT_EN_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV4_CTRL - */ -void mpu_setSlave4InterruptEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, - mpu_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 mpu_RA_I2C_SLV4_CTRL - */ -bool mpu_getSlave4WriteMode() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, - mpu_I2C_SLV4_REG_DIS_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV4_CTRL - */ -void mpu_setSlave4WriteMode(bool mode) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_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 mpu_RA_I2C_SLV4_CTRL - */ -uint8_t mpu_getSlave4MasterDelay() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, - mpu_I2C_SLV4_MST_DLY_BIT, mpu_I2C_SLV4_MST_DLY_LENGTH, mpu6050.buffer, - 0); - return mpu6050.buffer[0]; -} -/** Set Slave 4 master delay value. - * @param delay New Slave 4 master delay value - * @see getSlave4MasterDelay() - * @see mpu_RA_I2C_SLV4_CTRL - */ -void mpu_setSlave4MasterDelay(uint8_t delay) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, - mpu_I2C_SLV4_MST_DLY_BIT, mpu_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 mpu_RA_I2C_SLV4_DI - */ -uint8_t mpu_getSlate4InputByte() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_DI, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getPassthroughStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_PASS_THROUGH_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave4IsDone() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV4_DONE_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getLostArbitration() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_LOST_ARB_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave4Nack() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV4_NACK_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave3Nack() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV3_NACK_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave2Nack() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV2_NACK_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave1Nack() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV1_NACK_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_MST_STATUS - */ -bool mpu_getSlave0Nack() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, - mpu_MST_I2C_SLV0_NACK_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_LEVEL_BIT - */ -bool mpu_getInterruptMode() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_INT_LEVEL_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set interrupt logic level mode. - * @param mode New interrupt mode (0=active-high, 1=active-low) - * @see getInterruptMode() - * @see mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_LEVEL_BIT - */ -void mpu_setInterruptMode(bool mode) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_OPEN_BIT - */ -bool mpu_getInterruptDrive() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_INTCFG_INT_OPEN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set interrupt drive mode. - * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) - * @see getInterruptDrive() - * @see mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_OPEN_BIT - */ -void mpu_setInterruptDrive(bool drive) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_LATCH_INT_EN_BIT - */ -bool mpu_getInterruptLatch() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_LATCH_INT_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set interrupt latch mode. - * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) - * @see getInterruptLatch() - * @see mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_LATCH_INT_EN_BIT - */ -void mpu_setInterruptLatch(bool latch) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_RD_CLEAR_BIT - */ -bool mpu_getInterruptLatchClear() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_INT_RD_CLEAR_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_INT_RD_CLEAR_BIT - */ -void mpu_setInterruptLatchClear(bool clear) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_FSYNC_INT_LEVEL_BIT - */ -bool mpu_getFSyncInterruptLevel() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_FSYNC_INT_LEVEL_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_FSYNC_INT_LEVEL_BIT - */ -void mpu_setFSyncInterruptLevel(bool level) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_FSYNC_INT_EN_BIT - */ -bool mpu_getFSyncInterruptEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_FSYNC_INT_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set FSYNC pin interrupt enabled setting. - * @param enabled New FSYNC pin interrupt enabled setting - * @see getFSyncInterruptEnabled() - * @see mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_FSYNC_INT_EN_BIT - */ -void mpu_setFSyncInterruptEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_I2C_BYPASS_EN_BIT - */ -bool mpu_getI2CBypassEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_I2C_BYPASS_EN_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_I2C_BYPASS_EN_BIT - */ -void mpu_setI2CBypassEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_CLKOUT_EN_BIT - */ -bool mpu_getClockOutputEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, - mpu_INTCFG_CLKOUT_EN_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_PIN_CFG - * @see mpu_INTCFG_CLKOUT_EN_BIT - */ -void mpu_setClockOutputEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FF_BIT - **/ -uint8_t mpu_getIntEnabled() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu6050.buffer, 0); - 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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FF_BIT - **/ -void mpu_setIntEnabled(uint8_t enabled) { - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FF_BIT - **/ -bool mpu_getIntFreefallEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_FF_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Free Fall interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntFreefallEnabled() - * @see mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FF_BIT - **/ -void mpu_setIntFreefallEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_MOT_BIT - **/ -bool mpu_getIntMotionEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_MOT_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Motion Detection interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntMotionEnabled() - * @see mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_MOT_BIT - **/ -void mpu_setIntMotionEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_ZMOT_BIT - **/ -bool mpu_getIntZeroMotionEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_ZMOT_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Zero Motion Detection interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntZeroMotionEnabled() - * @see mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_ZMOT_BIT - **/ -void mpu_setIntZeroMotionEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FIFO_OFLOW_BIT - **/ -bool mpu_getIntFIFOBufferOverflowEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set FIFO Buffer Overflow interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntFIFOBufferOverflowEnabled() - * @see mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_FIFO_OFLOW_BIT - **/ -void mpu_setIntFIFOBufferOverflowEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_I2C_MST_INT_BIT - **/ -bool mpu_getIntI2CMasterEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set I2C Master interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntI2CMasterEnabled() - * @see mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_I2C_MST_INT_BIT - **/ -void mpu_setIntI2CMasterEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_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 mpu_RA_INT_ENABLE - * @see mpu_INTERRUPT_DATA_RDY_BIT - */ -bool mpu_getIntDataReadyEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Data Ready interrupt enabled status. - * @param enabled New interrupt enabled status - * @see getIntDataReadyEnabled() - * @see mpu_RA_INT_CFG - * @see mpu_INTERRUPT_DATA_RDY_BIT - */ -void mpu_setIntDataReadyEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, - mpu_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 mpu_RA_INT_STATUS - */ -uint8_t mpu_getIntStatus() { - I2Cdev_readByte(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_FF_BIT - */ -bool mpu_getIntFreefallStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_FF_BIT, - mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_MOT_BIT - */ -bool mpu_getIntMotionStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_MOT_BIT, - mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_ZMOT_BIT - */ -bool mpu_getIntZeroMotionStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_ZMOT_BIT, - mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_FIFO_OFLOW_BIT - */ -bool mpu_getIntFIFOBufferOverflowStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, - mpu_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_I2C_MST_INT_BIT - */ -bool mpu_getIntI2CMasterStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, - mpu_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer, 0); - 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 mpu_RA_INT_STATUS - * @see mpu_INTERRUPT_DATA_RDY_BIT - */ -bool mpu_getIntDataReadyStatus() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, - mpu_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer, 0); - 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 mpu_RA_ACCEL_XOUT_H - */ -void mpu_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) { - mpu_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 mpu_RA_ACCEL_XOUT_H - */ -void mpu_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, - int16_t* gy, int16_t* gz) { - I2Cdev_readBytes( - mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 14, mpu6050.buffer, 0); - *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 mpu_RA_GYRO_XOUT_H - */ -void mpu_getAcceleration(int16_t* x, int16_t* y, int16_t* z) { - // void mpu_getAcceleration(int32_t* x, int32_t* y, int32_t* z) { - I2Cdev_readBytes( - mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 6, mpu6050.buffer, 0); - *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 mpu_RA_ACCEL_XOUT_H - */ -int16_t mpu_getAccelerationX() { - I2Cdev_readBytes( - mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_ACCEL_YOUT_H - */ -int16_t mpu_getAccelerationY() { - I2Cdev_readBytes( - mpu6050.devAddr, mpu_RA_ACCEL_YOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_ACCEL_ZOUT_H - */ -int16_t mpu_getAccelerationZ() { - I2Cdev_readBytes( - mpu6050.devAddr, mpu_RA_ACCEL_ZOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_TEMP_OUT_H - */ -int16_t mpu_getTemperature() { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_TEMP_OUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_GYRO_XOUT_H - */ -void mpu_getRotation(int16_t* x, int16_t* y, int16_t* z) { - // void mpu_getRotation(int32_t* x, int32_t* y, int32_t* z) { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_XOUT_H, 6, mpu6050.buffer, 0); - *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 mpu_RA_GYRO_XOUT_H - */ -int16_t mpu_getRotationX() { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_XOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_GYRO_YOUT_H - */ -int16_t mpu_getRotationY() { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_YOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_RA_GYRO_ZOUT_H - */ -int16_t mpu_getRotationZ() { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_ZOUT_H, 2, mpu6050.buffer, 0); - 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 mpu_getExternalSensorByte(int position) { - I2Cdev_readByte( - mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, mpu6050.buffer, 0); - 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 mpu_getExternalSensorWord(int position) { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, 2, - mpu6050.buffer, 0); - 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 mpu_getExternalSensorDWord(int position) { - I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, 4, - mpu6050.buffer, 0); - 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 mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_XNEG_BIT - */ -bool mpu_getXNegMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_XNEG_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get X-axis positive motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_XPOS_BIT - */ -bool mpu_getXPosMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_XPOS_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get Y-axis negative motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_YNEG_BIT - */ -bool mpu_getYNegMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_YNEG_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get Y-axis positive motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_YPOS_BIT - */ -bool mpu_getYPosMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_YPOS_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get Z-axis negative motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_ZNEG_BIT - */ -bool mpu_getZNegMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_ZNEG_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get Z-axis positive motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_ZPOS_BIT - */ -bool mpu_getZPosMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_ZPOS_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Get zero motion detection interrupt status. - * @return Motion detection status - * @see mpu_RA_MOT_DETECT_STATUS - * @see mpu_MOTION_MOT_ZRMOT_BIT - */ -bool mpu_getZeroMotionDetected() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, - mpu_MOTION_MOT_ZRMOT_BIT, mpu6050.buffer, 0); - 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 mpu_RA_I2C_SLV0_DO - */ -void mpu_setSlaveOutputByte(uint8_t num, uint8_t data) { - if (num > 3) - return; - I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_MST_DELAY_CTRL - * @see mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT - */ -bool mpu_getExternalShadowDelayEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, - mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set external data shadow delay enabled status. - * @param enabled New external data shadow delay enabled status. - * @see getExternalShadowDelayEnabled() - * @see mpu_RA_I2C_MST_DELAY_CTRL - * @see mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT - */ -void mpu_setExternalShadowDelayEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, - mpu_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 mpu_RA_I2C_MST_DELAY_CTRL - * @see mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT - */ -bool mpu_getSlaveDelayEnabled(uint8_t num) { - // mpu_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. - if (num > 4) - return 0; - I2Cdev_readBit( - mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, num, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set slave delay enabled status. - * @param num Slave number (0-4) - * @param enabled New slave delay enabled status. - * @see mpu_RA_I2C_MST_DELAY_CTRL - * @see mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT - */ -void mpu_setSlaveDelayEnabled(uint8_t num, bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_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 mpu_RA_SIGNAL_PATH_RESET - * @see mpu_PATHRESET_GYRO_RESET_BIT - */ -void mpu_resetGyroscopePath() { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, - mpu_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 mpu_RA_SIGNAL_PATH_RESET - * @see mpu_PATHRESET_ACCEL_RESET_BIT - */ -void mpu_resetAccelerometerPath() { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, - mpu_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 mpu_RA_SIGNAL_PATH_RESET - * @see mpu_PATHRESET_TEMP_RESET_BIT - */ -void mpu_resetTemperaturePath() { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, - mpu_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 mpu_RA_MOT_DETECT_CTRL - * @see mpu_DETECT_ACCEL_ON_DELAY_BIT - */ -uint8_t mpu_getAccelerometerPowerOnDelay() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_ACCEL_ON_DELAY_BIT, mpu_DETECT_ACCEL_ON_DELAY_LENGTH, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set accelerometer power-on delay. - * @param delay New accelerometer power-on delay (0-3) - * @see getAccelerometerPowerOnDelay() - * @see mpu_RA_MOT_DETECT_CTRL - * @see mpu_DETECT_ACCEL_ON_DELAY_BIT - */ -void mpu_setAccelerometerPowerOnDelay(uint8_t delay) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_ACCEL_ON_DELAY_BIT, mpu_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 mpu_RA_MOT_DETECT_CTRL - * @see mpu_DETECT_FF_COUNT_BIT - */ -uint8_t mpu_getFreefallDetectionCounterDecrement() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_FF_COUNT_BIT, mpu_DETECT_FF_COUNT_LENGTH, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set Free Fall detection counter decrement configuration. - * @param decrement New decrement configuration value - * @see getFreefallDetectionCounterDecrement() - * @see mpu_RA_MOT_DETECT_CTRL - * @see mpu_DETECT_FF_COUNT_BIT - */ -void mpu_setFreefallDetectionCounterDecrement(uint8_t decrement) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_FF_COUNT_BIT, mpu_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 mpu_getMotionDetectionCounterDecrement() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_MOT_COUNT_BIT, mpu_DETECT_MOT_COUNT_LENGTH, mpu6050.buffer, - 0); - return mpu6050.buffer[0]; -} -/** Set Motion detection counter decrement configuration. - * @param decrement New decrement configuration value - * @see getMotionDetectionCounterDecrement() - * @see mpu_RA_MOT_DETECT_CTRL - * @see mpu_DETECT_MOT_COUNT_BIT - */ -void mpu_setMotionDetectionCounterDecrement(uint8_t decrement) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, - mpu_DETECT_MOT_COUNT_BIT, mpu_DETECT_MOT_COUNT_LENGTH, decrement); -} +#include "MpuController.hpp" +#include "Dispatcher.hpp" +#include "I2cController.hpp" +#include "MpuDmpCode.hpp" +#include "MpuDriver.hpp" +#include "utils/TickTimer.hpp" -// USER_CTRL register +#include "Bsp.hpp" -/** 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 mpu_RA_USER_CTRL - * @see mpu_USERCTRL_FIFO_EN_BIT - */ -bool mpu_getFIFOEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_FIFO_EN_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set FIFO enabled status. - * @param enabled New FIFO enabled status - * @see getFIFOEnabled() - * @see mpu_RA_USER_CTRL - * @see mpu_USERCTRL_FIFO_EN_BIT - */ -void mpu_setFIFOEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_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 mpu_RA_USER_CTRL - * @see mpu_USERCTRL_I2C_MST_EN_BIT - */ -bool mpu_getI2CMasterModeEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, - mpu_USERCTRL_I2C_MST_EN_BIT, mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set I2C Master Mode enabled status. - * @param enabled New I2C Master Mode enabled status - * @see getI2CMasterModeEnabled() - * @see mpu_RA_USER_CTRL - * @see mpu_USERCTRL_I2C_MST_EN_BIT - */ -void mpu_setI2CMasterModeEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, - mpu_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 mpu_switchSPIEnabled(bool enabled) { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, - mpu_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 mpu_RA_USER_CTRL - * @see mpu_USERCTRL_FIFO_RESET_BIT - */ -void mpu_resetFIFO() { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_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 mpu_RA_USER_CTRL - * @see mpu_USERCTRL_I2C_MST_RESET_BIT - */ -void mpu_resetI2CMaster() { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, - mpu_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 mpu_RA_USER_CTRL - * @see mpu_USERCTRL_SIG_COND_RESET_BIT - */ -void mpu_resetSensors() { - I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, - mpu_USERCTRL_SIG_COND_RESET_BIT, true); -} +#include "utils/QueueWrapper.hpp" +#include "utils/TaskWrapper.hpp" -// PWR_MGMT_1 register +#include "FreeRTOS.h" +#include "timers.h" -/** Trigger a full device reset. - * A small delay of ~50ms may be desirable after triggering a reset. - * @see mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_DEVICE_RESET_BIT - */ -void mpu_reset() { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_SLEEP_BIT - */ -bool mpu_getSleepEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_SLEEP_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set sleep mode status. - * @param enabled New sleep mode enabled status - * @see getSleepEnabled() - * @see mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_SLEEP_BIT - */ -void mpu_setSleepEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_CYCLE_BIT - */ -bool mpu_getWakeCycleEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CYCLE_BIT, - mpu6050.buffer, 0); - return mpu6050.buffer[0]; -} -/** Set wake cycle enabled status. - * @param enabled New sleep mode enabled status - * @see getWakeCycleEnabled() - * @see mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_CYCLE_BIT - */ -void mpu_setWakeCycleEnabled(bool enabled) { - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_TEMP_DIS_BIT - */ -bool mpu_getTempSensorEnabled() { - I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_TEMP_DIS_BIT, - mpu6050.buffer, 0); - 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 mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_TEMP_DIS_BIT - */ -void mpu_setTempSensorEnabled(bool enabled) { - // 1 is actually disabled here - I2Cdev_writeBit( - mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_TEMP_DIS_BIT, !enabled); -} -/** Get clock source setting. - * @return Current clock source setting - * @see mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_CLKSEL_BIT - * @see mpu_PWR1_CLKSEL_LENGTH - */ -uint8_t mpu_getClockSource() { - I2Cdev_readBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CLKSEL_BIT, - mpu_PWR1_CLKSEL_LENGTH, mpu6050.buffer, 0); - 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 mpu_RA_PWR_MGMT_1 - * @see mpu_PWR1_CLKSEL_BIT - * @see mpu_PWR1_CLKSEL_LENGTH - */ -void mpu_setClockSource(uint8_t source) { - I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CLKSEL_BIT, - mpu_PWR1_CLKSEL_LENGTH, source); -} +#include "event_groups.h" -// 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 mpu_RA_PWR_MGMT_2
- */
-uint8_t mpu_getWakeFrequency() {
-    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_2,
-        mpu_PWR2_LP_WAKE_CTRL_BIT, mpu_PWR2_LP_WAKE_CTRL_LENGTH, mpu6050.buffer,
-        0);
-    return mpu6050.buffer[0];
-}
-/** Set wake frequency in Accel-Only Low Power Mode.
- * @param frequency New wake frequency
- * @see mpu_RA_PWR_MGMT_2
- */
-void mpu_setWakeFrequency(uint8_t frequency) {
-    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_2,
-        mpu_PWR2_LP_WAKE_CTRL_BIT, mpu_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
-}
+#include 
 
-/** 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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_XA_BIT
- */
-bool mpu_getStandbyXAccelEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_XA_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set X-axis accelerometer standby enabled status.
- * @param New X-axis standby enabled status
- * @see getStandbyXAccelEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_XA_BIT
- */
-void mpu_setStandbyXAccelEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_YA_BIT
- */
-bool mpu_getStandbyYAccelEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_YA_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set Y-axis accelerometer standby enabled status.
- * @param New Y-axis standby enabled status
- * @see getStandbyYAccelEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_YA_BIT
- */
-void mpu_setStandbyYAccelEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_ZA_BIT
- */
-bool mpu_getStandbyZAccelEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_ZA_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set Z-axis accelerometer standby enabled status.
- * @param New Z-axis standby enabled status
- * @see getStandbyZAccelEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_ZA_BIT
- */
-void mpu_setStandbyZAccelEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_XG_BIT
- */
-bool mpu_getStandbyXGyroEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_XG_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set X-axis gyroscope standby enabled status.
- * @param New X-axis standby enabled status
- * @see getStandbyXGyroEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_XG_BIT
- */
-void mpu_setStandbyXGyroEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_YG_BIT
- */
-bool mpu_getStandbyYGyroEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_YG_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set Y-axis gyroscope standby enabled status.
- * @param New Y-axis standby enabled status
- * @see getStandbyYGyroEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_YG_BIT
- */
-void mpu_setStandbyYGyroEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_ZG_BIT
- */
-bool mpu_getStandbyZGyroEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_ZG_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-/** Set Z-axis gyroscope standby enabled status.
- * @param New Z-axis standby enabled status
- * @see getStandbyZGyroEnabled()
- * @see mpu_RA_PWR_MGMT_2
- * @see mpu_PWR2_STBY_ZG_BIT
- */
-void mpu_setStandbyZGyroEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_ZG_BIT, enabled);
-}
+struct MpuMotion32 {
+    CoprocStat_MpuQuaternion quat;
+    CoprocStat_MpuVector accel;
+    CoprocStat_MpuVector gyro;
+};
 
-// FIFO_COUNT* registers
+enum MpuSendType : uint8_t {
+    NEVER = 0,
+    ONCE = 1,
+    PERIODIC = 2,
+};
 
-/** 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 mpu_getFIFOCount() {
-    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_FIFO_COUNTH, 2, mpu6050.buffer, 0);
-    return (((uint16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
+static bool mpuInitialized = false;
+static MpuSendType mpuSendIndicator = MpuSendType::NEVER;
+static MpuMotion32 mpuAggrData;
+static constexpr uint32_t mpuTickPeriodMs = 10;
+static uint32_t mpuAggrCounter = 0;
+static uint16_t compressCoef = 4;
 
-// 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 mpu_getFIFOByte() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FIFO_R_W, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_getFIFOBytes(uint8_t* data, uint8_t length) {
-    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_FIFO_R_W, length, data, 0);
-}
-/** Write byte to FIFO mpu6050.buffer.
- * @see getFIFOByte()
- * @see mpu_RA_FIFO_R_W
- */
-void mpu_setFIFOByte(uint8_t data) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_FIFO_R_W, data);
+void mpuReset() {
+    if (mpuInitialized) {
+        HAL_NVIC_DisableIRQ(EXTI15_10_IRQn);
+        mpu_setDMPEnabled(false);
+        mpuInitialized = false;
+        mpuSendIndicator = MpuSendType::NEVER;
+    }
 }
 
-// WHO_AM_I register
+void mpuCreate() { mpu6050.devAddr = mpu_ADDRESS_AD0_HIGH; }
 
-/** 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 mpu_RA_WHO_AM_I
- * @see mpu_WHO_AM_I_BIT
- * @see mpu_WHO_AM_I_LENGTH
- */
-uint8_t mpu_getDeviceID() {
-    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_WHO_AM_I, mpu_WHO_AM_I_BIT,
-        mpu_WHO_AM_I_LENGTH, mpu6050.buffer, 0);
-    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 mpu_RA_WHO_AM_I
- * @see mpu_WHO_AM_I_BIT
- * @see mpu_WHO_AM_I_LENGTH
+/** 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 mpu_setDeviceID(uint8_t id) {
-    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_WHO_AM_I, mpu_WHO_AM_I_BIT,
-        mpu_WHO_AM_I_LENGTH, id);
-}
+void mpuInitialize() {
+    if (mpuInitialized) {
+        return;
+    }
+    mpuInitialized = true;
 
-// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+    mpu_reset();
+    vTaskDelay(pdMS_TO_TICKS(50));
 
-// XG_OFFS_TC register
+    if (!mpu_testConnection()) {
+        DEBUG("MPU6050 is not connected\n");
+        CoprocStat status = {
+            .which_payload = CoprocStat_faultStat_tag,
+            .payload = { 
+                .faultStat = {
+                    .which_fault = CoprocStat_FaultStat_mpuFault_tag,
+                },
+            },
+        };
+        dispatcherEnqueueStatus(status);
+        return;
+    }
 
-uint8_t mpu_getOTPBankValid() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OTP_BNK_VLD_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setOTPBankValid(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OTP_BNK_VLD_BIT, enabled);
-}
-int8_t mpu_getXGyroOffsetTC() {
-    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setXGyroOffsetTC(int8_t offset) {
-    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, offset);
-}
+    mpu_setSleepEnabled(false);
 
-// YG_OFFS_TC register
+    mpu_setClockSource(mpu_CLOCK_PLL_ZGYRO);
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_INT_ENABLE,
+        1 << mpu_INTERRUPT_FIFO_OFLOW_BIT | 1 << mpu_INTERRUPT_DMP_INT_BIT);
+    mpu_setRate(4);
+    mpu_setExternalFrameSync(mpu_EXT_SYNC_TEMP_OUT_L);
+    mpu_setDLPFMode(mpu_DLPF_BW_42);
+    mpu_setFullScaleGyroRange(mpu_GYRO_FS_2000);
+    mpu_setFullScaleAccelRange(mpu_ACCEL_FS_2);
 
-int8_t mpu_getYGyroOffsetTC() {
-    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setYGyroOffsetTC(int8_t offset) {
-    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, offset);
-}
+    mpu_writeMemoryBlock(dmpCode20, sizeof(dmpCode20));
 
-// ZG_OFFS_TC register
+    unsigned char dmpUpdate[] = { 0x00, 1 };
+    mpu_writeMemoryBlock(dmpUpdate, 0x02, 0x02,
+        0x16); // Lets write the dmpUpdate data to the Firmware image, we have 2 bytes to write in bank 0x02 with the Offset 0x16
 
-int8_t mpu_getZGyroOffsetTC() {
-    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ZG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setZGyroOffsetTC(int8_t offset) {
-    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ZG_OFFS_TC, mpu_TC_OFFSET_BIT,
-        mpu_TC_OFFSET_LENGTH, offset);
-}
+    mpu_setDMPConfig1(0x03);
+    mpu_setDMPConfig2(0x00);
+    mpu_setOTPBankValid(false);
 
-// X_FINE_GAIN register
+    mpu_setFIFOEnabled(true);
 
-int8_t mpu_getXFineGain() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_X_FINE_GAIN, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setXFineGain(int8_t gain) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_X_FINE_GAIN, gain);
-}
+    mpu_setDMPEnabled(false);
+    mpu_resetFIFO();
+    mpu_resetDMP();
 
-// Y_FINE_GAIN register
+    mpu_setOTPBankValid(false);
 
-int8_t mpu_getYFineGain() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_Y_FINE_GAIN, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setYFineGain(int8_t gain) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_Y_FINE_GAIN, gain);
+    mpu_setDMPEnabled(true);
+    HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
 }
 
-// Z_FINE_GAIN register
-
-int8_t mpu_getZFineGain() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_Z_FINE_GAIN, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setZFineGain(int8_t gain) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_Z_FINE_GAIN, gain);
-}
+void mpuOnIntTriggered() { i2cSetEventFlagFromIsr(I2C_MPU_TICK); }
 
-// XA_OFFS_* registers
+static void mpuCalculateYawPitchRoll(
+    const CoprocStat_MpuQuaternion& q, CoprocStat_MpuVector& yawPitchRoll) {
+    const float qw = (q.w / compressCoef) / 16384.f;
+    const float qx = (q.x / compressCoef) / 16384.f;
+    const float qy = (q.y / compressCoef) / 16384.f;
+    const float qz = (q.z / compressCoef) / 16384.f;
 
-int16_t mpu_getXAccelOffset() {
-    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_XA_OFFS_H, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setXAccelOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_XA_OFFS_H, offset);
-}
+    const float gx = 2 * (qx * qz - qw * qy);
+    const float gy = 2 * (qw * qx + qy * qz);
+    const float gz = qw * qw - qx * qx - qy * qy + qz * qz;
 
-// YA_OFFS_* register
+    const constexpr float PI = 3.14159f;
 
-int16_t mpu_getYAccelOffset() {
-    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_YA_OFFS_H, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setYAccelOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_YA_OFFS_H, offset);
-}
+    float ex = atan2f(2 * qx * qy - 2 * qw * qz, 2 * qw * qw + 2 * qx * qx - 1)
+        * (180.f / PI);
+    float ey = atan2f(gx, sqrtf(gy * gy + gz * gz)) * (180.f / PI);
+    float ez = atan2f(gy, gz) * (180.f / PI);
 
-// ZA_OFFS_* register
+    if (gz < 0) {
+        if (ey > 0) {
+            ey = PI - ey;
+        } else {
+            ey = -PI - ey;
+        }
+    }
 
-int16_t mpu_getZAccelOffset() {
-    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_ZA_OFFS_H, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setZAccelOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_ZA_OFFS_H, offset);
+    yawPitchRoll.x = ex * 16384.f;
+    yawPitchRoll.y = ey * 16384.f;
+    yawPitchRoll.z = ez * 16384.f;
 }
 
-// XG_OFFS_USR* registers
+static void mpuSend(const MpuMotion32& data) {
+    // DEBUG(
+    //     "DEBUG MPU SEND [%d] acc: x:%d; y:%d; z:%d | gyro: x:%d; y:%d; z:%d\n",
+    //     mpuAggrCounter, data.accel.x, data.accel.y, data.accel.z, data.gyro.x,
+    //     data.gyro.y, data.gyro.z);
 
-int16_t mpu_getXGyroOffset() {
-    I2Cdev_readBytes(
-        mpu6050.devAddr, mpu_RA_XG_OFFS_USRH, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setXGyroOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_XG_OFFS_USRH, offset);
-}
+    CoprocStat status = {
+        .which_payload = CoprocStat_mpuStat_tag,
+    };
 
-// YG_OFFS_USR* register
+    auto& mpuStat = status.payload.mpuStat;
 
-int16_t mpu_getYGyroOffset() {
-    I2Cdev_readBytes(
-        mpu6050.devAddr, mpu_RA_YG_OFFS_USRH, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setYGyroOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_YG_OFFS_USRH, offset);
-}
+    memcpy(&mpuStat.accel, &mpuAggrData.accel, sizeof(CoprocStat_MpuVector));
+    mpuStat.has_accel = true;
 
-// ZG_OFFS_USR* register
+    memcpy(&mpuStat.gyro, &mpuAggrData.gyro, sizeof(CoprocStat_MpuVector));
+    mpuStat.has_gyro = true;
 
-int16_t mpu_getZGyroOffset() {
-    I2Cdev_readBytes(
-        mpu6050.devAddr, mpu_RA_ZG_OFFS_USRH, 2, mpu6050.buffer, 0);
-    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
-}
-void mpu_setZGyroOffset(int16_t offset) {
-    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_ZG_OFFS_USRH, offset);
-}
+    memcpy(&mpuStat.quat, &mpuAggrData.quat, sizeof(CoprocStat_MpuQuaternion));
+    mpuStat.has_quat = true;
 
-// INT_ENABLE register (DMP functions)
+    mpuCalculateYawPitchRoll(mpuStat.quat, mpuStat.yawPitchRoll);
+    mpuStat.has_yawPitchRoll = true;
 
-bool mpu_getIntPLLReadyEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
-        mpu_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setIntPLLReadyEnabled(bool enabled) {
-    I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
-        mpu_INTERRUPT_PLL_RDY_INT_BIT, enabled);
-}
-bool mpu_getIntDMPEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
-        mpu_INTERRUPT_DMP_INT_BIT, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_setIntDMPEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_DMP_INT_BIT, enabled);
+    mpuStat.compressCoef = compressCoef;
+    dispatcherEnqueueStatus(status);
 }
 
-// DMP_INT_STATUS
+void mpuTick() {
+    uint16_t fifoCount = mpu_getFIFOCount();
+    if (fifoCount >= 1024) {
+        DEBUG("fifo overflow, resetting");
+        mpu_resetFIFO();
+        return;
+    }
 
-bool mpu_getDMPInt5Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_5_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getDMPInt4Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_4_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getDMPInt3Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_3_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getDMPInt2Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_2_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getDMPInt1Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_1_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getDMPInt0Status() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_0_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
+    std::array packet;
 
-// INT_STATUS register (DMP functions)
+    while (fifoCount >= packet.size()) {
+        int read_res = I2Cdev_readBytes(
+            mpu6050.devAddr, mpu_RA_FIFO_R_W, packet.size(), packet.data(), 0);
+        if (read_res < 0) {
+            break;
+        }
 
-bool mpu_getIntPLLReadyStatus() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS,
-        mpu_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-bool mpu_getIntDMPStatus() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS,
-        mpu_INTERRUPT_DMP_INT_BIT, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
+        const int16_t qw = (packet[0] << 8) | packet[1];
+        const int16_t qx = (packet[4] << 8) | packet[5];
+        const int16_t qy = (packet[8] << 8) | packet[9];
+        const int16_t qz = (packet[12] << 8) | packet[13];
+
+        const int16_t ax = (packet[28] << 8) | packet[29];
+        const int16_t ay = (packet[32] << 8) | packet[33];
+        const int16_t az = (packet[36] << 8) | packet[37];
+
+        const int16_t gx = (packet[16] << 8) | packet[17];
+        const int16_t gy = (packet[20] << 8) | packet[21];
+        const int16_t gz = (packet[24] << 8) | packet[25];
+
+        mpuAggrData.quat.w += qw;
+        mpuAggrData.quat.x += qx;
+        mpuAggrData.quat.y += qy;
+        mpuAggrData.quat.z += qz;
+
+        mpuAggrData.accel.x += ax;
+        mpuAggrData.accel.y += ay;
+        mpuAggrData.accel.z += az;
+
+        mpuAggrData.gyro.x += gx;
+        mpuAggrData.gyro.y += gy;
+        mpuAggrData.gyro.z += gz;
+
+        mpuAggrCounter++;
+        if (mpuAggrCounter >= compressCoef) {
+            if (mpuSendIndicator) {
+                mpuSend(mpuAggrData);
+                if (mpuSendIndicator == MpuSendType::ONCE) {
+                    mpuSendIndicator = MpuSendType::NEVER;
+                }
+            }
 
-// USER_CTRL register (DMP functions)
+            memset(&mpuAggrData, 0, sizeof(mpuAggrData));
+            mpuAggrCounter = 0;
+        }
 
-bool mpu_getDMPEnabled() {
-    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_EN_BIT,
-        mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
+        fifoCount -= read_res;
+    }
 }
-void mpu_setDMPEnabled(bool enabled) {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_EN_BIT, enabled);
+
+static int16_t readMpuOffsetReg(uint8_t addr) {
+    uint8_t data[2];
+    I2Cdev_readBytes(mpu6050.devAddr, addr, 2, data, 0);
+    return (((int16_t)data[0]) << 8) | data[1];
 }
-void mpu_resetDMP() {
-    I2Cdev_writeBit(
-        mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_RESET_BIT, true);
+
+static void writeMpuOffsetReg(uint8_t addr, int16_t value) {
+    uint8_t data[2] = { uint8_t(((uint16_t)value) >> 8),
+        uint8_t(((uint16_t)value) & 0xFF) };
+    I2Cdev_writeBytes(mpu6050.devAddr, addr, 2, data);
 }
 
-// BANK_SEL register
+static void mpuCalibrationPid(uint8_t addr_read, uint8_t addr_write,
+    uint16_t loops, float kP, float kI, bool is_accel,
+    int16_t out_calibration_data[3]) {
+    const uint8_t write_stride = 2;
+    uint8_t bit_zero[3];
+    float i_term[3];
 
-void mpu_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
-    bank &= 0x1F;
-    if (userBank)
-        bank |= 0x20;
-    if (prefetchEnabled)
-        bank |= 0x40;
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_BANK_SEL, bank);
-}
+    uint16_t gravity = 0;
+    if (is_accel) {
+        gravity = 16384 >> mpu_getFullScaleAccelRange();
+    }
 
-// MEM_START_ADDR register
+    const uint16_t target_error = is_accel ? 100 : 5;
 
-void mpu_setMemoryStartAddress(uint8_t address) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_MEM_START_ADDR, address);
-}
+    DEBUG("Starting MPU calibration\n");
 
-// MEM_R_W register
+    for (int i = 0; i < 3; i++) {
+        int16_t data;
+        data = readMpuOffsetReg(addr_write + (i * write_stride));
 
-uint8_t mpu_readMemoryByte() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MEM_R_W, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
-}
-void mpu_writeMemoryByte(uint8_t data) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_MEM_R_W, data);
-}
-void mpu_readMemoryBlock(
-    uint8_t* data, uint16_t dataSize, uint8_t bank, uint8_t address) {
-    mpu_setMemoryBank(bank, false, false);
-    mpu_setMemoryStartAddress(address);
-    uint8_t chunkSize;
-    for (uint16_t i = 0; i < dataSize;) {
-        // determine correct chunk size according to bank position and data size
-        chunkSize = mpu_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, mpu_RA_MEM_R_W, chunkSize, data + i, 0);
-
-        // 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++;
-            mpu_setMemoryBank(bank, false, false);
-            mpu_setMemoryStartAddress(address);
-        }
-    }
-}
-/*bool mpu_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
-    mpu_setMemoryBank(bank, false, false);
-    mpu_setMemoryStartAddress(address);
-    uint8_t chunkSize;
-    uint8_t *verifyBuffer;
-    uint8_t *progBuffer;
-    uint16_t i;
-    uint8_t j;
-    if (verify) verifyBuffer = (uint8_t *)malloc(mpu_DMP_MEMORY_CHUNK_SIZE);
-    if (useProgMem) progBuffer = (uint8_t *)malloc(mpu_DMP_MEMORY_CHUNK_SIZE);
-    for (i = 0; i < dataSize;) {
-        // determine correct chunk size according to bank position and data size
-        chunkSize = mpu_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);
+        // Capture Bit Zero to properly handle Accelerometer calibration
+        if (is_accel) {
+            bit_zero[i] = data & 1;
+            i_term[i] = data * 8.f;
         } else {
-            // write the chunk of data as specified
-            progBuffer = (uint8_t *)data + i;
+            i_term[i] = data * 4.f;
         }
+    }
 
-        I2Cdev_writeBytes(mpu6050.devAddr, mpu_RA_MEM_R_W, chunkSize, progBuffer);
-
-        // verify data if needed
-        if (verify && verifyBuffer) {
-            mpu_setMemoryBank(bank, false, false);
-            mpu_setMemoryStartAddress(address);
-            I2Cdev_readBytes(mpu6050.devAddr, mpu_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.
-            }
-        }
+    for (uint16_t loop_iter = 0; loop_iter < loops; ++loop_iter) {
+        uint16_t readings_within_margin = 0;
+        for (uint16_t sample_idx = 0; sample_idx < 0xFFFFF; ++sample_idx) {
+            uint32_t readings_sum = 0;
 
-        // increase byte index by [chunkSize]
-        i += chunkSize;
+            for (int i = 0; i < 3; i++) {
+                int16_t reading_16 = 0;
+                reading_16 = readMpuOffsetReg(addr_read + (i * 2));
 
-        // uint8_t automatically wraps to 0 at 256
-        address += chunkSize;
+                int32_t reading = reading_16;
 
-        // if we aren't done, update bank (if necessary) and address
-        if (i < dataSize) {
-            if (address == 0) bank++;
-            mpu_setMemoryBank(bank, false, false);
-            mpu_setMemoryStartAddress(address);
-        }
-    }
-    if (verify) free(verifyBuffer);
-    if (useProgMem) free(progBuffer);
-    return true;
-}
-bool mpu_writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
-    return mpu_writeMemoryBlock(data, dataSize, bank, address, verify, true);
-}
-bool mpu_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
-    }
+                if (is_accel && i == 2) {
+                    reading -= gravity;
+                }
 
-    // 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++];
-        }
+                readings_sum += abs(reading);
 
-        // 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;
+                float error = -reading;
+                float p_term = kP * error;
+                i_term[i] += (error * 0.001f) * kI;
+
+                int16_t computed_offset;
+                if (is_accel) {
+                    computed_offset = round((p_term + i_term[i]) / 8);
+                    computed_offset = (computed_offset & 0xFFFE) | bit_zero[i];
+                } else {
+                    computed_offset = round((p_term + i_term[i]) / 4);
+                }
+
+                //DEBUG("  %d: %d %d -> %d\n", i, reading, reading_16, computed_offset);
+
+                writeMpuOffsetReg(
+                    addr_write + (i * write_stride), computed_offset);
             }
-            success = mpu_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++];
+
+            if (sample_idx % 100 == 99) {
+                DEBUG("* %lu\n", readings_sum);
             }
-            //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, mpu_RA_INT_ENABLE, 0x32);  // single operation
-
-                success = true;
-            } else {
-                // unknown special command
-                success = false;
+
+            if (readings_sum < target_error) {
+                ++readings_within_margin;
+            }
+
+            if (readings_sum < target_error && sample_idx > 10
+                && readings_within_margin >= 10) {
+                break;
             }
+            vTaskDelay(pdMS_TO_TICKS(1));
         }
-        
-        if (!success) {
-            if (useProgMem) free(progBuffer);
-            return false; // uh oh
+
+        DEBUG(".\n");
+        kP *= .75f;
+        kI *= .75f;
+
+        for (int i = 0; i < 3; i++) {
+            int16_t computed_offset;
+            if (is_accel) {
+                computed_offset = round(i_term[i] / 8);
+                computed_offset = (computed_offset & 0xFFFE) | bit_zero[i];
+            } else {
+                computed_offset = round(i_term[i] / 4);
+            }
+
+            out_calibration_data[i] = computed_offset;
+            writeMpuOffsetReg(addr_write + (i * write_stride), computed_offset);
         }
     }
-    if (useProgMem) free(progBuffer);
-    return true;
-}
-bool mpu_writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
-    return mpu_writeDMPConfigurationSet(data, dataSize, true);
-}*/
 
-// DMP_CFG_1 register
+    mpu_resetFIFO();
+    mpu_resetDMP();
+}
 
-uint8_t mpu_getDMPConfig1() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_DMP_CFG_1, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
+static void mpuCalibrateAccel(int16_t out_calibration_data[3]) {
+    mpuCalibrationPid(mpu_RA_ACCEL_XOUT_H, mpu_RA_XA_OFFS_H, 5, 0.3f, 20.f,
+        true, out_calibration_data);
 }
-void mpu_setDMPConfig1(uint8_t config) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_DMP_CFG_1, config);
+
+static void mpuCalibrateGyro(int16_t out_calibration_data[3]) {
+    mpuCalibrationPid(mpu_RA_GYRO_XOUT_H, mpu_RA_XG_OFFS_USRH, 5, 0.3f, 90.f,
+        false, out_calibration_data);
 }
 
-// DMP_CFG_2 register
+static void mpuRestoreCalibrationData(const MpuCalibrationData& data) {
+    const uint8_t write_stride = 2;
+
+    auto data_cast = (const int16_t*)data.data;
+
+    for (int i = 0; i < 3; i++) {
+        writeMpuOffsetReg(mpu_RA_XA_OFFS_H + (i * write_stride), data_cast[i]);
+    }
+
+    for (int i = 0; i < 3; i++) {
+        writeMpuOffsetReg(
+            mpu_RA_XG_OFFS_USRH + (i * write_stride), data_cast[i + 3]);
+    }
+
+    mpu_resetFIFO();
+    mpu_resetDMP();
 
-uint8_t mpu_getDMPConfig2() {
-    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_DMP_CFG_2, mpu6050.buffer, 0);
-    return mpu6050.buffer[0];
+    if (mpuInitialized) {
+        mpu_setDMPEnabled(true);
+    }
 }
-void mpu_setDMPConfig2(uint8_t config) {
-    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_DMP_CFG_2, config);
+
+void mpuDispatch(const CoprocReq_MpuReq& req) {
+    switch (req.which_mpuCmd) {
+    case CoprocReq_MpuReq_init_tag:
+        mpuInitialize();
+        break;
+    case CoprocReq_MpuReq_oneSend_tag: {
+        if (mpuSendIndicator == MpuSendType::NEVER) {
+            mpuSendIndicator = MpuSendType::ONCE;
+        }
+        break;
+    }
+    case CoprocReq_MpuReq_startSend_tag: {
+        mpuSendIndicator = MpuSendType::PERIODIC;
+        break;
+    }
+    case CoprocReq_MpuReq_stopSend_tag: {
+        mpuSendIndicator = MpuSendType::NEVER;
+        break;
+    }
+    case CoprocReq_MpuReq_setCompressCoef_tag: {
+        uint16_t coef = req.mpuCmd.setCompressCoef;
+        if (coef > 0 && coef <= 20) {
+            compressCoef = coef;
+            DEBUGLN("MPU6050 set new compression coef: %d", compressCoef);
+        }
+        break;
+    }
+    case CoprocReq_MpuReq_getCompressCoef_tag: {
+        CoprocStat status = {
+            .which_payload = CoprocStat_mpuStat_tag,
+            .payload = {
+                .mpuStat = {
+                    .compressCoef = compressCoef,
+                },
+            },
+        };
+        dispatcherEnqueueStatus(status);
+        break;
+    }
+    case CoprocReq_MpuReq_calibrateOffsets_tag: {
+        DEBUG("Calibrating MPU offsets\n");
+        int16_t calibration_data[6] = {};
+        mpuCalibrateAccel(calibration_data);
+        mpuCalibrateGyro(calibration_data + 3);
+
+        CoprocStat status = {
+            .which_payload = CoprocStat_mpuCalibrationDone_tag,
+        };
+        static_assert(sizeof(status.payload.mpuCalibrationDone.data)
+            == sizeof(calibration_data));
+        memcpy(status.payload.mpuCalibrationDone.data, calibration_data,
+            sizeof(calibration_data));
+        dispatcherEnqueueStatus(status);
+        break;
+    }
+    case CoprocReq_MpuReq_restoreCalibrationData_tag: {
+        mpuRestoreCalibrationData(req.mpuCmd.restoreCalibrationData);
+        break;
+    }
+    };
 }
diff --git a/fw/rbcx-coprocessor/src/MpuDriver.cpp b/fw/rbcx-coprocessor/src/MpuDriver.cpp
new file mode 100644
index 00000000..08abd4cc
--- /dev/null
+++ b/fw/rbcx-coprocessor/src/MpuDriver.cpp
@@ -0,0 +1,3259 @@
+// I2Cdev library collection - mpu 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
+//     2017-03-28 - tested basic function on STM32
+
+// 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 "MpuDriver.hpp"
+#include "I2cController.hpp"
+#include "utils/Debug.hpp"
+
+mpu_t mpu6050;
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool mpu_testConnection() { return mpu_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 mpu_getAuxVDDIOLevel() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_PWR_MODE_BIT,
+        mpu6050.buffer, 0);
+    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 mpu_setAuxVDDIOLevel(uint8_t level) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_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 mpu_RA_SMPLRT_DIV
+ */
+uint8_t mpu_getRate() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_SMPLRT_DIV, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see mpu_RA_SMPLRT_DIV
+ */
+void mpu_setRate(uint8_t rate) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_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.
+ *
+ * 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 mpu_getExternalFrameSync() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_EXT_SYNC_SET_BIT, + mpu_CFG_EXT_SYNC_SET_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see mpu_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void mpu_setExternalFrameSync(uint8_t sync) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_EXT_SYNC_SET_BIT, + mpu_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 mpu_RA_CONFIG + * @see mpu_CFG_DLPF_CFG_BIT + * @see mpu_CFG_DLPF_CFG_LENGTH + */ +uint8_t mpu_getDLPFMode() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_DLPF_CFG_BIT, + mpu_CFG_DLPF_CFG_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see mpu_DLPF_BW_256 + * @see mpu_RA_CONFIG + * @see mpu_CFG_DLPF_CFG_BIT + * @see mpu_CFG_DLPF_CFG_LENGTH + */ +void mpu_setDLPFMode(uint8_t mode) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_CONFIG, mpu_CFG_DLPF_CFG_BIT, + mpu_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 mpu_GYRO_FS_250 + * @see mpu_RA_GYRO_CONFIG + * @see mpu_GCONFIG_FS_SEL_BIT + * @see mpu_GCONFIG_FS_SEL_LENGTH + */ +uint8_t mpu_getFullScaleGyroRange() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_GYRO_CONFIG, mpu_GCONFIG_FS_SEL_BIT, + mpu_GCONFIG_FS_SEL_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see mpu_GYRO_FS_250 + * @see mpu_RA_GYRO_CONFIG + * @see mpu_GCONFIG_FS_SEL_BIT + * @see mpu_GCONFIG_FS_SEL_LENGTH + */ +void mpu_setFullScaleGyroRange(uint8_t range) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_GYRO_CONFIG, + mpu_GCONFIG_FS_SEL_BIT, mpu_GCONFIG_FS_SEL_LENGTH, range); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +bool mpu_getAccelXSelfTest() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_XA_ST_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +void mpu_setAccelXSelfTest(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +bool mpu_getAccelYSelfTest() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_YA_ST_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +void mpu_setAccelYSelfTest(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +bool mpu_getAccelZSelfTest() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_ACONFIG_ZA_ST_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see mpu_RA_ACCEL_CONFIG + */ +void mpu_setAccelZSelfTest(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, mpu_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 mpu_ACCEL_FS_2 + * @see mpu_RA_ACCEL_CONFIG + * @see mpu_ACONFIG_AFS_SEL_BIT + * @see mpu_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t mpu_getFullScaleAccelRange() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, + mpu_ACONFIG_AFS_SEL_BIT, mpu_ACONFIG_AFS_SEL_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void mpu_setFullScaleAccelRange(uint8_t range) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, + mpu_ACONFIG_AFS_SEL_BIT, mpu_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 mpu_DHPF_RESET + * @see mpu_RA_ACCEL_CONFIG + */ +uint8_t mpu_getDHPFMode() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, + mpu_ACONFIG_ACCEL_HPF_BIT, mpu_ACONFIG_ACCEL_HPF_LENGTH, mpu6050.buffer, + 0); + return mpu6050.buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see mpu_DHPF_RESET + * @see mpu_RA_ACCEL_CONFIG + */ +void mpu_setDHPFMode(uint8_t bandwidth) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ACCEL_CONFIG, + mpu_ACONFIG_ACCEL_HPF_BIT, mpu_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 mpu_RA_FF_THR + */ +uint8_t mpu_getFreefallDetectionThreshold() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FF_THR, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see mpu_RA_FF_THR + */ +void mpu_setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_FF_DUR + */ +uint8_t mpu_getFreefallDetectionDuration() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FF_DUR, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see mpu_RA_FF_DUR + */ +void mpu_setFreefallDetectionDuration(uint8_t duration) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_MOT_THR + */ +uint8_t mpu_getMotionDetectionThreshold() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MOT_THR, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set free-fall event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see mpu_RA_MOT_THR + */ +void mpu_setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_MOT_DUR + */ +uint8_t mpu_getMotionDetectionDuration() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MOT_DUR, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see mpu_RA_MOT_DUR + */ +void mpu_setMotionDetectionDuration(uint8_t duration) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_ZRMOT_THR + */ +uint8_t mpu_getZeroMotionDetectionThreshold() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_ZRMOT_THR, mpu6050.buffer, 0); + 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 mpu_RA_ZRMOT_THR + */ +void mpu_setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_ZRMOT_DUR + */ +uint8_t mpu_getZeroMotionDetectionDuration() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_ZRMOT_DUR, mpu6050.buffer, 0); + 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 mpu_RA_ZRMOT_DUR + */ +void mpu_setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getTempFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_TEMP_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setTempFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getXGyroFIFOEnabled() { + I2Cdev_readBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_XG_FIFO_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setXGyroFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getYGyroFIFOEnabled() { + I2Cdev_readBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_YG_FIFO_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setYGyroFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getZGyroFIFOEnabled() { + I2Cdev_readBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_ZG_FIFO_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setZGyroFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getAccelFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_ACCEL_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setAccelFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getSlave2FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV2_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setSlave2FIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getSlave1FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV1_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setSlave1FIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_FIFO_EN + */ +bool mpu_getSlave0FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_SLV0_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see mpu_RA_FIFO_EN + */ +void mpu_setSlave0FIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_FIFO_EN, mpu_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 mpu_RA_I2C_MST_CTRL + */ +bool mpu_getMultiMasterEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_MULT_MST_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see mpu_RA_I2C_MST_CTRL + */ +void mpu_setMultiMasterEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL + */ +bool mpu_getWaitForExternalSensorEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_WAIT_FOR_ES_BIT, + mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_CTRL + */ +void mpu_setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_MST_CTRL + */ +bool mpu_getSlave3FIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_SLV_3_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see mpu_RA_MST_CTRL + */ +void mpu_setSlave3FIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL + */ +bool mpu_getSlaveReadWriteTransitionEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_P_NSR_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see mpu_RA_I2C_MST_CTRL + */ +void mpu_setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_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 mpu_RA_I2C_MST_CTRL + */ +uint8_t mpu_getMasterClockSpeed() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_CLK_BIT, + mpu_I2C_MST_CLK_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see mpu_RA_I2C_MST_CTRL + */ +void mpu_setMasterClockSpeed(uint8_t speed) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_MST_CTRL, mpu_I2C_MST_CLK_BIT, + mpu_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 mpu_RA_I2C_SLV0_ADDR + */ +uint8_t mpu_getSlaveAddress(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readByte( + mpu6050.devAddr, mpu_RA_I2C_SLV0_ADDR + num * 3, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_ADDR + */ +void mpu_setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) + return; + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV0_REG + */ +uint8_t mpu_getSlaveRegister(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readByte( + mpu6050.devAddr, mpu_RA_I2C_SLV0_REG + num * 3, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_REG + */ +void mpu_setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) + return; + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV0_CTRL + */ +bool mpu_getSlaveEnabled(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_EN_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_CTRL + */ +void mpu_setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) + return; + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_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 mpu_RA_I2C_SLV0_CTRL + */ +bool mpu_getSlaveWordByteSwap(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_BYTE_SW_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_CTRL + */ +void mpu_setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) + return; + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_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 mpu_RA_I2C_SLV0_CTRL + */ +bool mpu_getSlaveWriteMode(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_REG_DIS_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_CTRL + */ +void mpu_setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) + return; + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_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 mpu_RA_I2C_SLV0_CTRL + */ +bool mpu_getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_GRP_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_CTRL + */ +void mpu_setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) + return; + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_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 mpu_RA_I2C_SLV0_CTRL + */ +uint8_t mpu_getSlaveDataLength(uint8_t num) { + if (num > 3) + return 0; + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_LEN_BIT, mpu_I2C_SLV_LEN_LENGTH, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_CTRL + */ +void mpu_setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) + return; + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_SLV0_CTRL + num * 3, + mpu_I2C_SLV_LEN_BIT, mpu_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 mpu_RA_I2C_SLV4_ADDR + */ +uint8_t mpu_getSlave4Address() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_ADDR, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see mpu_RA_I2C_SLV4_ADDR + */ +void mpu_setSlave4Address(uint8_t address) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_REG + */ +uint8_t mpu_getSlave4Register() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_REG, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see mpu_RA_I2C_SLV4_REG + */ +void mpu_setSlave4Register(uint8_t reg) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_DO + */ +void mpu_setSlave4OutputByte(uint8_t data) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_SLV4_CTRL + */ +bool mpu_getSlave4Enabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_I2C_SLV4_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see mpu_RA_I2C_SLV4_CTRL + */ +void mpu_setSlave4Enabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_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 mpu_RA_I2C_SLV4_CTRL + */ +bool mpu_getSlave4InterruptEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, + mpu_I2C_SLV4_INT_EN_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV4_CTRL + */ +void mpu_setSlave4InterruptEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, + mpu_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 mpu_RA_I2C_SLV4_CTRL + */ +bool mpu_getSlave4WriteMode() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, + mpu_I2C_SLV4_REG_DIS_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV4_CTRL + */ +void mpu_setSlave4WriteMode(bool mode) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, mpu_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 mpu_RA_I2C_SLV4_CTRL + */ +uint8_t mpu_getSlave4MasterDelay() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, + mpu_I2C_SLV4_MST_DLY_BIT, mpu_I2C_SLV4_MST_DLY_LENGTH, mpu6050.buffer, + 0); + return mpu6050.buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see mpu_RA_I2C_SLV4_CTRL + */ +void mpu_setSlave4MasterDelay(uint8_t delay) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_I2C_SLV4_CTRL, + mpu_I2C_SLV4_MST_DLY_BIT, mpu_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 mpu_RA_I2C_SLV4_DI + */ +uint8_t mpu_getSlate4InputByte() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_I2C_SLV4_DI, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getPassthroughStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_PASS_THROUGH_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave4IsDone() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV4_DONE_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getLostArbitration() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_LOST_ARB_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave4Nack() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV4_NACK_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave3Nack() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV3_NACK_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave2Nack() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV2_NACK_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave1Nack() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV1_NACK_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_MST_STATUS + */ +bool mpu_getSlave0Nack() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_STATUS, + mpu_MST_I2C_SLV0_NACK_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_LEVEL_BIT + */ +bool mpu_getInterruptMode() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_INT_LEVEL_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_LEVEL_BIT + */ +void mpu_setInterruptMode(bool mode) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_OPEN_BIT + */ +bool mpu_getInterruptDrive() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_INTCFG_INT_OPEN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_OPEN_BIT + */ +void mpu_setInterruptDrive(bool drive) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_LATCH_INT_EN_BIT + */ +bool mpu_getInterruptLatch() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_LATCH_INT_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_LATCH_INT_EN_BIT + */ +void mpu_setInterruptLatch(bool latch) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_RD_CLEAR_BIT + */ +bool mpu_getInterruptLatchClear() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_INT_RD_CLEAR_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_INT_RD_CLEAR_BIT + */ +void mpu_setInterruptLatchClear(bool clear) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool mpu_getFSyncInterruptLevel() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_FSYNC_INT_LEVEL_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void mpu_setFSyncInterruptLevel(bool level) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_FSYNC_INT_EN_BIT + */ +bool mpu_getFSyncInterruptEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_FSYNC_INT_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_FSYNC_INT_EN_BIT + */ +void mpu_setFSyncInterruptEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_I2C_BYPASS_EN_BIT + */ +bool mpu_getI2CBypassEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_I2C_BYPASS_EN_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_I2C_BYPASS_EN_BIT + */ +void mpu_setI2CBypassEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_CLKOUT_EN_BIT + */ +bool mpu_getClockOutputEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_PIN_CFG, + mpu_INTCFG_CLKOUT_EN_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_PIN_CFG + * @see mpu_INTCFG_CLKOUT_EN_BIT + */ +void mpu_setClockOutputEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_PIN_CFG, mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FF_BIT + **/ +uint8_t mpu_getIntEnabled() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu6050.buffer, 0); + 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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FF_BIT + **/ +void mpu_setIntEnabled(uint8_t enabled) { + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FF_BIT + **/ +bool mpu_getIntFreefallEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_FF_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FF_BIT + **/ +void mpu_setIntFreefallEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_MOT_BIT + **/ +bool mpu_getIntMotionEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_MOT_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_MOT_BIT + **/ +void mpu_setIntMotionEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_ZMOT_BIT + **/ +bool mpu_getIntZeroMotionEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_ZMOT_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_ZMOT_BIT + **/ +void mpu_setIntZeroMotionEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool mpu_getIntFIFOBufferOverflowEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_FIFO_OFLOW_BIT + **/ +void mpu_setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_I2C_MST_INT_BIT + **/ +bool mpu_getIntI2CMasterEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_I2C_MST_INT_BIT + **/ +void mpu_setIntI2CMasterEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_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 mpu_RA_INT_ENABLE + * @see mpu_INTERRUPT_DATA_RDY_BIT + */ +bool mpu_getIntDataReadyEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see mpu_RA_INT_CFG + * @see mpu_INTERRUPT_DATA_RDY_BIT + */ +void mpu_setIntDataReadyEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE, + mpu_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 mpu_RA_INT_STATUS + */ +uint8_t mpu_getIntStatus() { + I2Cdev_readByte(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_FF_BIT + */ +bool mpu_getIntFreefallStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_FF_BIT, + mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_MOT_BIT + */ +bool mpu_getIntMotionStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_MOT_BIT, + mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_ZMOT_BIT + */ +bool mpu_getIntZeroMotionStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, mpu_INTERRUPT_ZMOT_BIT, + mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_FIFO_OFLOW_BIT + */ +bool mpu_getIntFIFOBufferOverflowStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, + mpu_INTERRUPT_FIFO_OFLOW_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_I2C_MST_INT_BIT + */ +bool mpu_getIntI2CMasterStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, + mpu_INTERRUPT_I2C_MST_INT_BIT, mpu6050.buffer, 0); + 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 mpu_RA_INT_STATUS + * @see mpu_INTERRUPT_DATA_RDY_BIT + */ +bool mpu_getIntDataReadyStatus() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS, + mpu_INTERRUPT_DATA_RDY_BIT, mpu6050.buffer, 0); + 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 mpu_RA_ACCEL_XOUT_H + */ +void mpu_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) { + mpu_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 mpu_RA_ACCEL_XOUT_H + */ +void mpu_getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, + int16_t* gy, int16_t* gz) { + I2Cdev_readBytes( + mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 14, mpu6050.buffer, 0); + *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 mpu_RA_GYRO_XOUT_H + */ +void mpu_getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + // void mpu_getAcceleration(int32_t* x, int32_t* y, int32_t* z) { + I2Cdev_readBytes( + mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 6, mpu6050.buffer, 0); + *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 mpu_RA_ACCEL_XOUT_H + */ +int16_t mpu_getAccelerationX() { + I2Cdev_readBytes( + mpu6050.devAddr, mpu_RA_ACCEL_XOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_ACCEL_YOUT_H + */ +int16_t mpu_getAccelerationY() { + I2Cdev_readBytes( + mpu6050.devAddr, mpu_RA_ACCEL_YOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_ACCEL_ZOUT_H + */ +int16_t mpu_getAccelerationZ() { + I2Cdev_readBytes( + mpu6050.devAddr, mpu_RA_ACCEL_ZOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_TEMP_OUT_H + */ +int16_t mpu_getTemperature() { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_TEMP_OUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_GYRO_XOUT_H + */ +void mpu_getRotation(int16_t* x, int16_t* y, int16_t* z) { + // void mpu_getRotation(int32_t* x, int32_t* y, int32_t* z) { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_XOUT_H, 6, mpu6050.buffer, 0); + *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 mpu_RA_GYRO_XOUT_H + */ +int16_t mpu_getRotationX() { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_XOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_GYRO_YOUT_H + */ +int16_t mpu_getRotationY() { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_YOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_RA_GYRO_ZOUT_H + */ +int16_t mpu_getRotationZ() { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_GYRO_ZOUT_H, 2, mpu6050.buffer, 0); + 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 mpu_getExternalSensorByte(int position) { + I2Cdev_readByte( + mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, mpu6050.buffer, 0); + 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 mpu_getExternalSensorWord(int position) { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, 2, + mpu6050.buffer, 0); + 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 mpu_getExternalSensorDWord(int position) { + I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_EXT_SENS_DATA_00 + position, 4, + mpu6050.buffer, 0); + 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 mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_XNEG_BIT + */ +bool mpu_getXNegMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_XNEG_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_XPOS_BIT + */ +bool mpu_getXPosMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_XPOS_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_YNEG_BIT + */ +bool mpu_getYNegMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_YNEG_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_YPOS_BIT + */ +bool mpu_getYPosMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_YPOS_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_ZNEG_BIT + */ +bool mpu_getZNegMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_ZNEG_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_ZPOS_BIT + */ +bool mpu_getZPosMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_ZPOS_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see mpu_RA_MOT_DETECT_STATUS + * @see mpu_MOTION_MOT_ZRMOT_BIT + */ +bool mpu_getZeroMotionDetected() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_MOT_DETECT_STATUS, + mpu_MOTION_MOT_ZRMOT_BIT, mpu6050.buffer, 0); + 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 mpu_RA_I2C_SLV0_DO + */ +void mpu_setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) + return; + I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_I2C_MST_DELAY_CTRL + * @see mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool mpu_getExternalShadowDelayEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, + mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see mpu_RA_I2C_MST_DELAY_CTRL + * @see mpu_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void mpu_setExternalShadowDelayEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, + mpu_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 mpu_RA_I2C_MST_DELAY_CTRL + * @see mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool mpu_getSlaveDelayEnabled(uint8_t num) { + // mpu_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) + return 0; + I2Cdev_readBit( + mpu6050.devAddr, mpu_RA_I2C_MST_DELAY_CTRL, num, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see mpu_RA_I2C_MST_DELAY_CTRL + * @see mpu_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void mpu_setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_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 mpu_RA_SIGNAL_PATH_RESET + * @see mpu_PATHRESET_GYRO_RESET_BIT + */ +void mpu_resetGyroscopePath() { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, + mpu_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 mpu_RA_SIGNAL_PATH_RESET + * @see mpu_PATHRESET_ACCEL_RESET_BIT + */ +void mpu_resetAccelerometerPath() { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, + mpu_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 mpu_RA_SIGNAL_PATH_RESET + * @see mpu_PATHRESET_TEMP_RESET_BIT + */ +void mpu_resetTemperaturePath() { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_SIGNAL_PATH_RESET, + mpu_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 mpu_RA_MOT_DETECT_CTRL + * @see mpu_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t mpu_getAccelerometerPowerOnDelay() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_ACCEL_ON_DELAY_BIT, mpu_DETECT_ACCEL_ON_DELAY_LENGTH, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see mpu_RA_MOT_DETECT_CTRL + * @see mpu_DETECT_ACCEL_ON_DELAY_BIT + */ +void mpu_setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_ACCEL_ON_DELAY_BIT, mpu_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 mpu_RA_MOT_DETECT_CTRL + * @see mpu_DETECT_FF_COUNT_BIT + */ +uint8_t mpu_getFreefallDetectionCounterDecrement() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_FF_COUNT_BIT, mpu_DETECT_FF_COUNT_LENGTH, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see mpu_RA_MOT_DETECT_CTRL + * @see mpu_DETECT_FF_COUNT_BIT + */ +void mpu_setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_FF_COUNT_BIT, mpu_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 mpu_getMotionDetectionCounterDecrement() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_MOT_COUNT_BIT, mpu_DETECT_MOT_COUNT_LENGTH, mpu6050.buffer, + 0); + return mpu6050.buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see mpu_RA_MOT_DETECT_CTRL + * @see mpu_DETECT_MOT_COUNT_BIT + */ +void mpu_setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_MOT_DETECT_CTRL, + mpu_DETECT_MOT_COUNT_BIT, mpu_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 mpu_RA_USER_CTRL + * @see mpu_USERCTRL_FIFO_EN_BIT + */ +bool mpu_getFIFOEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_FIFO_EN_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see mpu_RA_USER_CTRL + * @see mpu_USERCTRL_FIFO_EN_BIT + */ +void mpu_setFIFOEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_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 mpu_RA_USER_CTRL + * @see mpu_USERCTRL_I2C_MST_EN_BIT + */ +bool mpu_getI2CMasterModeEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, + mpu_USERCTRL_I2C_MST_EN_BIT, mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see mpu_RA_USER_CTRL + * @see mpu_USERCTRL_I2C_MST_EN_BIT + */ +void mpu_setI2CMasterModeEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, + mpu_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 mpu_switchSPIEnabled(bool enabled) { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, + mpu_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 mpu_RA_USER_CTRL + * @see mpu_USERCTRL_FIFO_RESET_BIT + */ +void mpu_resetFIFO() { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_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 mpu_RA_USER_CTRL + * @see mpu_USERCTRL_I2C_MST_RESET_BIT + */ +void mpu_resetI2CMaster() { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, + mpu_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 mpu_RA_USER_CTRL + * @see mpu_USERCTRL_SIG_COND_RESET_BIT + */ +void mpu_resetSensors() { + I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_USER_CTRL, + mpu_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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_DEVICE_RESET_BIT + */ +void mpu_reset() { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_SLEEP_BIT + */ +bool mpu_getSleepEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_SLEEP_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_SLEEP_BIT + */ +void mpu_setSleepEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_CYCLE_BIT + */ +bool mpu_getWakeCycleEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CYCLE_BIT, + mpu6050.buffer, 0); + return mpu6050.buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_CYCLE_BIT + */ +void mpu_setWakeCycleEnabled(bool enabled) { + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_TEMP_DIS_BIT + */ +bool mpu_getTempSensorEnabled() { + I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_TEMP_DIS_BIT, + mpu6050.buffer, 0); + 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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_TEMP_DIS_BIT + */ +void mpu_setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev_writeBit( + mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_CLKSEL_BIT + * @see mpu_PWR1_CLKSEL_LENGTH + */ +uint8_t mpu_getClockSource() { + I2Cdev_readBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CLKSEL_BIT, + mpu_PWR1_CLKSEL_LENGTH, mpu6050.buffer, 0); + 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 mpu_RA_PWR_MGMT_1 + * @see mpu_PWR1_CLKSEL_BIT + * @see mpu_PWR1_CLKSEL_LENGTH + */ +void mpu_setClockSource(uint8_t source) { + I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_1, mpu_PWR1_CLKSEL_BIT, + mpu_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 mpu_RA_PWR_MGMT_2
+ */
+uint8_t mpu_getWakeFrequency() {
+    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_2,
+        mpu_PWR2_LP_WAKE_CTRL_BIT, mpu_PWR2_LP_WAKE_CTRL_LENGTH, mpu6050.buffer,
+        0);
+    return mpu6050.buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see mpu_RA_PWR_MGMT_2
+ */
+void mpu_setWakeFrequency(uint8_t frequency) {
+    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_PWR_MGMT_2,
+        mpu_PWR2_LP_WAKE_CTRL_BIT, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_XA_BIT
+ */
+bool mpu_getStandbyXAccelEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_XA_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_XA_BIT
+ */
+void mpu_setStandbyXAccelEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_YA_BIT
+ */
+bool mpu_getStandbyYAccelEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_YA_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_YA_BIT
+ */
+void mpu_setStandbyYAccelEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_ZA_BIT
+ */
+bool mpu_getStandbyZAccelEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_ZA_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_ZA_BIT
+ */
+void mpu_setStandbyZAccelEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_XG_BIT
+ */
+bool mpu_getStandbyXGyroEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_XG_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_XG_BIT
+ */
+void mpu_setStandbyXGyroEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_YG_BIT
+ */
+bool mpu_getStandbyYGyroEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_YG_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_YG_BIT
+ */
+void mpu_setStandbyYGyroEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_ZG_BIT
+ */
+bool mpu_getStandbyZGyroEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_PWR2_STBY_ZG_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see mpu_RA_PWR_MGMT_2
+ * @see mpu_PWR2_STBY_ZG_BIT
+ */
+void mpu_setStandbyZGyroEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_PWR_MGMT_2, mpu_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 mpu_getFIFOCount() {
+    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_FIFO_COUNTH, 2, mpu6050.buffer, 0);
+    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 mpu_getFIFOByte() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_FIFO_R_W, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_getFIFOBytes(uint8_t* data, uint8_t length) {
+    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_FIFO_R_W, length, data, 0);
+}
+/** Write byte to FIFO mpu6050.buffer.
+ * @see getFIFOByte()
+ * @see mpu_RA_FIFO_R_W
+ */
+void mpu_setFIFOByte(uint8_t data) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_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 mpu_RA_WHO_AM_I
+ * @see mpu_WHO_AM_I_BIT
+ * @see mpu_WHO_AM_I_LENGTH
+ */
+uint8_t mpu_getDeviceID() {
+    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_WHO_AM_I, mpu_WHO_AM_I_BIT,
+        mpu_WHO_AM_I_LENGTH, mpu6050.buffer, 0);
+    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 mpu_RA_WHO_AM_I
+ * @see mpu_WHO_AM_I_BIT
+ * @see mpu_WHO_AM_I_LENGTH
+ */
+void mpu_setDeviceID(uint8_t id) {
+    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_WHO_AM_I, mpu_WHO_AM_I_BIT,
+        mpu_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t mpu_getOTPBankValid() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OTP_BNK_VLD_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setOTPBankValid(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t mpu_getXGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setXGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_XG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t mpu_getYGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setYGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_YG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t mpu_getZGyroOffsetTC() {
+    I2Cdev_readBits(mpu6050.devAddr, mpu_RA_ZG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setZGyroOffsetTC(int8_t offset) {
+    I2Cdev_writeBits(mpu6050.devAddr, mpu_RA_ZG_OFFS_TC, mpu_TC_OFFSET_BIT,
+        mpu_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t mpu_getXFineGain() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_X_FINE_GAIN, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setXFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t mpu_getYFineGain() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_Y_FINE_GAIN, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setYFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t mpu_getZFineGain() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_Z_FINE_GAIN, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setZFineGain(int8_t gain) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t mpu_getXAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_XA_OFFS_H, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setXAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t mpu_getYAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_YA_OFFS_H, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setYAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t mpu_getZAccelOffset() {
+    I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_ZA_OFFS_H, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setZAccelOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t mpu_getXGyroOffset() {
+    I2Cdev_readBytes(
+        mpu6050.devAddr, mpu_RA_XG_OFFS_USRH, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setXGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t mpu_getYGyroOffset() {
+    I2Cdev_readBytes(
+        mpu6050.devAddr, mpu_RA_YG_OFFS_USRH, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setYGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t mpu_getZGyroOffset() {
+    I2Cdev_readBytes(
+        mpu6050.devAddr, mpu_RA_ZG_OFFS_USRH, 2, mpu6050.buffer, 0);
+    return (((int16_t)mpu6050.buffer[0]) << 8) | mpu6050.buffer[1];
+}
+void mpu_setZGyroOffset(int16_t offset) {
+    I2Cdev_writeWord(mpu6050.devAddr, mpu_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool mpu_getIntPLLReadyEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
+        mpu_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setIntPLLReadyEnabled(bool enabled) {
+    I2Cdev_writeBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
+        mpu_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool mpu_getIntDMPEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_ENABLE,
+        mpu_INTERRUPT_DMP_INT_BIT, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setIntDMPEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_INT_ENABLE, mpu_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool mpu_getDMPInt5Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_5_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getDMPInt4Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_4_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getDMPInt3Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_3_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getDMPInt2Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_2_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getDMPInt1Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_1_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getDMPInt0Status() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_DMP_INT_STATUS, mpu_DMPINT_0_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool mpu_getIntPLLReadyStatus() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS,
+        mpu_INTERRUPT_PLL_RDY_INT_BIT, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+bool mpu_getIntDMPStatus() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_INT_STATUS,
+        mpu_INTERRUPT_DMP_INT_BIT, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool mpu_getDMPEnabled() {
+    I2Cdev_readBit(mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_EN_BIT,
+        mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setDMPEnabled(bool enabled) {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_EN_BIT, enabled);
+}
+void mpu_resetDMP() {
+    I2Cdev_writeBit(
+        mpu6050.devAddr, mpu_RA_USER_CTRL, mpu_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void mpu_setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
+    bank &= 0x1F;
+    if (userBank)
+        bank |= 0x20;
+    if (prefetchEnabled)
+        bank |= 0x40;
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void mpu_setMemoryStartAddress(uint8_t address) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t mpu_readMemoryByte() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_MEM_R_W, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_writeMemoryByte(uint8_t data) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_MEM_R_W, data);
+}
+void mpu_readMemoryBlock(
+    uint8_t* data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    mpu_setMemoryBank(bank, false, false);
+    mpu_setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = mpu_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, mpu_RA_MEM_R_W, chunkSize, data + i, 0);
+
+        // 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++;
+            mpu_setMemoryBank(bank, false, false);
+            mpu_setMemoryStartAddress(address);
+        }
+    }
+}
+
+void mpu_writeMemoryBlock(
+    const uint8_t* data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    mpu_setMemoryBank(bank, false, false);
+    mpu_setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint16_t i;
+
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = mpu_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 (!I2Cdev_writeBytes(
+                mpu6050.devAddr, mpu_RA_MEM_R_W, chunkSize, data + i))
+            DEBUG("Write not ok\n");
+
+        if (true) {
+            mpu_setMemoryBank(bank, false, false);
+            mpu_setMemoryStartAddress(address);
+            uint8_t verifyBuf[mpu_DMP_MEMORY_CHUNK_SIZE];
+            memset(verifyBuf, 0xFE, sizeof(verifyBuf));
+            I2Cdev_readBytes(mpu6050.devAddr, mpu_RA_MEM_R_W, chunkSize,
+                verifyBuf, I2CDEV_DEFAULT_READ_TIMEOUT * 10);
+            if (memcmp(data + i, verifyBuf, chunkSize) != 0) {
+                DEBUG("Block write verification error, bank %d, address %d\n",
+                    bank, address);
+
+                char buf[128] = {};
+                char* buf_ptr = buf;
+                int buf_rem = sizeof(buf);
+                for (int j = 0; j < chunkSize; j++) {
+                    int printed
+                        = snprintf(buf_ptr, buf_rem, "%02x", data[i + j]);
+                    buf_ptr += printed;
+                    buf_rem -= printed;
+                }
+                DEBUG("%s\n", buf);
+
+                buf_ptr = buf;
+                buf_rem = sizeof(buf);
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    int printed
+                        = snprintf(buf_ptr, buf_rem, "%02x", verifyBuf[j]);
+                    buf_ptr += printed;
+                    buf_rem -= printed;
+                }
+                DEBUG("%s\n", buf);
+            }
+        }
+
+        // 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++;
+            mpu_setMemoryBank(bank, false, false);
+            mpu_setMemoryStartAddress(address);
+        }
+    }
+}
+
+// DMP_CFG_1 register
+
+uint8_t mpu_getDMPConfig1() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_DMP_CFG_1, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setDMPConfig1(uint8_t config) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t mpu_getDMPConfig2() {
+    I2Cdev_readByte(mpu6050.devAddr, mpu_RA_DMP_CFG_2, mpu6050.buffer, 0);
+    return mpu6050.buffer[0];
+}
+void mpu_setDMPConfig2(uint8_t config) {
+    I2Cdev_writeByte(mpu6050.devAddr, mpu_RA_DMP_CFG_2, config);
+}