From 24da6a37982ec5f5f2214f5e6f459b730e5c5fa7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Bj=C3=B6rn=20Ellensohn?= Date: Mon, 10 Jul 2023 11:54:53 +0200 Subject: [PATCH] update repo --- config/config.h | 34 + config/custom/beebo_config.h | 84 + config/custom/beebo_m_config.h | 84 + config/custom/dev_config.h | 84 + config/custom/square_config.h | 84 + config/lino_base_config.h | 176 + firmware/.gitignore | 5 + firmware/.vscode/extensions.json | 10 + firmware/.vscode/settings.json | 10 + firmware/include/README | 39 + firmware/lib/encoder/encoder.cpp | 10 + firmware/lib/encoder/encoder.h | 1005 ++++++ firmware/lib/encoder/examples/Basic/Basic.pde | 29 + .../examples/NoInterrupts/NoInterrupts.pde | 46 + .../encoder/examples/SpeedTest/SpeedTest.pde | 113 + .../encoder/examples/TwoKnobs/TwoKnobs.pde | 46 + firmware/lib/encoder/keywords.txt | 4 + .../lib/encoder/utility/direct_pin_read.h | 110 + .../lib/encoder/utility/interrupt_config.h | 87 + firmware/lib/encoder/utility/interrupt_pins.h | 369 ++ firmware/lib/imu/ADXL345.cpp | 1668 +++++++++ firmware/lib/imu/ADXL345.h | 361 ++ firmware/lib/imu/HMC5883L.cpp | 365 ++ firmware/lib/imu/HMC5883L.h | 148 + firmware/lib/imu/I2Cdev.cpp | 1461 ++++++++ firmware/lib/imu/I2Cdev.h | 280 ++ firmware/lib/imu/ITG3200.cpp | 521 +++ firmware/lib/imu/ITG3200.h | 179 + firmware/lib/imu/MPU6050.cpp | 3213 +++++++++++++++++ firmware/lib/imu/MPU6050.h | 1032 ++++++ firmware/lib/imu/MPU9150.cpp | 3167 ++++++++++++++++ firmware/lib/imu/MPU9150.h | 1040 ++++++ firmware/lib/imu/MPU9250.cpp | 3170 ++++++++++++++++ firmware/lib/imu/MPU9250.h | 1043 ++++++ firmware/lib/imu/default_imu.h | 400 ++ firmware/lib/imu/fake_mag.h | 38 + firmware/lib/imu/imu.h | 48 + firmware/lib/imu/imu_interface.h | 101 + firmware/lib/kinematics/kinematics.cpp | 149 + firmware/lib/kinematics/kinematics.h | 69 + firmware/lib/motor/default_motor.h | 220 ++ firmware/lib/motor/motor.h | 43 + firmware/lib/motor/motor_interface.h | 46 + firmware/lib/odometry/odometry.cpp | 92 + firmware/lib/odometry/odometry.h | 39 + firmware/lib/pid/pid.cpp | 54 + firmware/lib/pid/pid.h | 38 + firmware/platformio.ini | 94 + firmware/src/firmware.ino | 311 ++ readme.md | 1 + 50 files changed, 21820 insertions(+) create mode 100644 config/config.h create mode 100644 config/custom/beebo_config.h create mode 100644 config/custom/beebo_m_config.h create mode 100644 config/custom/dev_config.h create mode 100644 config/custom/square_config.h create mode 100644 config/lino_base_config.h create mode 100644 firmware/.gitignore create mode 100644 firmware/.vscode/extensions.json create mode 100644 firmware/.vscode/settings.json create mode 100644 firmware/include/README create mode 100644 firmware/lib/encoder/encoder.cpp create mode 100644 firmware/lib/encoder/encoder.h create mode 100644 firmware/lib/encoder/examples/Basic/Basic.pde create mode 100644 firmware/lib/encoder/examples/NoInterrupts/NoInterrupts.pde create mode 100644 firmware/lib/encoder/examples/SpeedTest/SpeedTest.pde create mode 100644 firmware/lib/encoder/examples/TwoKnobs/TwoKnobs.pde create mode 100644 firmware/lib/encoder/keywords.txt create mode 100644 firmware/lib/encoder/utility/direct_pin_read.h create mode 100644 firmware/lib/encoder/utility/interrupt_config.h create mode 100644 firmware/lib/encoder/utility/interrupt_pins.h create mode 100644 firmware/lib/imu/ADXL345.cpp create mode 100644 firmware/lib/imu/ADXL345.h create mode 100644 firmware/lib/imu/HMC5883L.cpp create mode 100644 firmware/lib/imu/HMC5883L.h create mode 100644 firmware/lib/imu/I2Cdev.cpp create mode 100644 firmware/lib/imu/I2Cdev.h create mode 100644 firmware/lib/imu/ITG3200.cpp create mode 100644 firmware/lib/imu/ITG3200.h create mode 100644 firmware/lib/imu/MPU6050.cpp create mode 100644 firmware/lib/imu/MPU6050.h create mode 100644 firmware/lib/imu/MPU9150.cpp create mode 100644 firmware/lib/imu/MPU9150.h create mode 100644 firmware/lib/imu/MPU9250.cpp create mode 100644 firmware/lib/imu/MPU9250.h create mode 100644 firmware/lib/imu/default_imu.h create mode 100644 firmware/lib/imu/fake_mag.h create mode 100644 firmware/lib/imu/imu.h create mode 100644 firmware/lib/imu/imu_interface.h create mode 100644 firmware/lib/kinematics/kinematics.cpp create mode 100644 firmware/lib/kinematics/kinematics.h create mode 100644 firmware/lib/motor/default_motor.h create mode 100644 firmware/lib/motor/motor.h create mode 100644 firmware/lib/motor/motor_interface.h create mode 100644 firmware/lib/odometry/odometry.cpp create mode 100644 firmware/lib/odometry/odometry.h create mode 100644 firmware/lib/pid/pid.cpp create mode 100644 firmware/lib/pid/pid.h create mode 100644 firmware/platformio.ini create mode 100644 firmware/src/firmware.ino create mode 100644 readme.md diff --git a/config/config.h b/config/config.h new file mode 100644 index 0000000..c0676e7 --- /dev/null +++ b/config/config.h @@ -0,0 +1,34 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifdef USE_BEEBO_CONFIG + #include "custom/beebo_config.h" +#endif + +#ifdef USE_BEEBO_M_CONFIG + #include "custom/beebo_m_config.h" +#endif + +#ifdef USE_SQUARE_CONFIG + #include "custom/square_config.h" +#endif + +#ifdef USE_DEV_CONFIG + #include "custom/dev_config.h" +#endif + +#if !defined (USE_BEEBO_CONFIG) && !defined (USE_DEV_CONFIG) && !defined (USE_SQUARE_CONFIG) && !defined (USE_BEEBO_M_CONFIG) + #include "lino_base_config.h" +#endif + diff --git a/config/custom/beebo_config.h b/config/custom/beebo_config.h new file mode 100644 index 0000000..d3c25d9 --- /dev/null +++ b/config/custom/beebo_config.h @@ -0,0 +1,84 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEEBO_CONFIG_H +#define BEEBO_CONFIG_H + +#define LED_PIN 13 + +#define LINO_BASE SKID_STEER + +#define USE_GENERIC_1_IN_MOTOR_DRIVER +#define USE_GY85_IMU + +#define K_P 0.6 +#define K_I 0.8 +#define K_D 0.5 + +#define MOTOR_MAX_RPM 140 +#define MAX_RPM_RATIO 0.85 +#define MOTOR_OPERATING_VOLTAGE 24 +#define MOTOR_POWER_MAX_VOLTAGE 14.6 +#define MOTOR_POWER_MEASURED_VOLTAGE 14.6 +#define COUNTS_PER_REV1 144384 +#define COUNTS_PER_REV2 140777 +#define COUNTS_PER_REV3 148326 +#define COUNTS_PER_REV4 144495 +#define WHEEL_DIAMETER 0.152 +#define LR_WHEELS_DISTANCE 0.271 +#define PWM_BITS 10 +#define PWM_FREQUENCY 20000 + +/// ENCODER PINS +#define MOTOR1_ENCODER_A 14 +#define MOTOR1_ENCODER_B 15 +#define MOTOR1_ENCODER_INV false + +#define MOTOR2_ENCODER_A 11 +#define MOTOR2_ENCODER_B 12 +#define MOTOR2_ENCODER_INV false + +#define MOTOR3_ENCODER_A 17 +#define MOTOR3_ENCODER_B 16 +#define MOTOR3_ENCODER_INV true + +#define MOTOR4_ENCODER_A 9 +#define MOTOR4_ENCODER_B 10 +#define MOTOR4_ENCODER_INV false + +// Motor Pins +#define MOTOR1_PWM 21 +#define MOTOR1_IN_A 20 +#define MOTOR1_IN_B -1 +#define MOTOR1_INV false + +#define MOTOR2_PWM 5 +#define MOTOR2_IN_A 6 +#define MOTOR2_IN_B -1 +#define MOTOR2_INV true + +#define MOTOR3_PWM 22 +#define MOTOR3_IN_A 23 +#define MOTOR3_IN_B -1 +#define MOTOR3_INV false + +#define MOTOR4_PWM 4 +#define MOTOR4_IN_A 3 +#define MOTOR4_IN_B -1 +#define MOTOR4_INV false + +#define PWM_MAX pow(2, PWM_BITS) - 1 +#define PWM_MIN -PWM_MAX + +#endif diff --git a/config/custom/beebo_m_config.h b/config/custom/beebo_m_config.h new file mode 100644 index 0000000..f24fadd --- /dev/null +++ b/config/custom/beebo_m_config.h @@ -0,0 +1,84 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef BEEBO_M_CONFIG_H +#define BEEBO_M_CONFIG_H + +#define LED_PIN 13 + +#define LINO_BASE MECANUM + +#define USE_GENERIC_1_IN_MOTOR_DRIVER +#define USE_GY85_IMU + +#define K_P 0.6 +#define K_I 0.8 +#define K_D 0.5 + +#define MOTOR_MAX_RPM 140 +#define MAX_RPM_RATIO 0.85 +#define MOTOR_OPERATING_VOLTAGE 24 +#define MOTOR_POWER_MAX_VOLTAGE 14.6 +#define MOTOR_POWER_MEASURED_VOLTAGE 14.6 +#define COUNTS_PER_REV1 144384 +#define COUNTS_PER_REV2 140777 +#define COUNTS_PER_REV3 148326 +#define COUNTS_PER_REV4 144495 +#define WHEEL_DIAMETER 0.1 +#define LR_WHEELS_DISTANCE 0.31 +#define PWM_BITS 10 +#define PWM_FREQUENCY 20000 + +/// ENCODER PINS +#define MOTOR1_ENCODER_A 14 +#define MOTOR1_ENCODER_B 15 +#define MOTOR1_ENCODER_INV false + +#define MOTOR2_ENCODER_A 11 +#define MOTOR2_ENCODER_B 12 +#define MOTOR2_ENCODER_INV false + +#define MOTOR3_ENCODER_A 17 +#define MOTOR3_ENCODER_B 16 +#define MOTOR3_ENCODER_INV true + +#define MOTOR4_ENCODER_A 9 +#define MOTOR4_ENCODER_B 10 +#define MOTOR4_ENCODER_INV false + +// Motor Pins +#define MOTOR1_PWM 21 +#define MOTOR1_IN_A 20 +#define MOTOR1_IN_B -1 +#define MOTOR1_INV false + +#define MOTOR2_PWM 5 +#define MOTOR2_IN_A 6 +#define MOTOR2_IN_B -1 +#define MOTOR2_INV true + +#define MOTOR3_PWM 22 +#define MOTOR3_IN_A 23 +#define MOTOR3_IN_B -1 +#define MOTOR3_INV false + +#define MOTOR4_PWM 4 +#define MOTOR4_IN_A 3 +#define MOTOR4_IN_B -1 +#define MOTOR4_INV false + +#define PWM_MAX pow(2, PWM_BITS) - 1 +#define PWM_MIN -PWM_MAX + +#endif diff --git a/config/custom/dev_config.h b/config/custom/dev_config.h new file mode 100644 index 0000000..f06618a --- /dev/null +++ b/config/custom/dev_config.h @@ -0,0 +1,84 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef DEV_CONFIG_H +#define DEV_CONFIG_H + +#define LED_PIN 13 + +#define LINO_BASE SKID_STEER + +#define USE_GENERIC_1_IN_MOTOR_DRIVER +#define USE_FAKE_IMU + +#define K_P 0.6 +#define K_I 0.8 +#define K_D 0.5 + +#define MOTOR_MAX_RPM 140 +#define MAX_RPM_RATIO 0.85 +#define MOTOR_OPERATING_VOLTAGE 24 +#define MOTOR_POWER_MAX_VOLTAGE 12 +#define MOTOR_POWER_MEASURED_VOLTAGE 12 +#define COUNTS_PER_REV1 144000 +#define COUNTS_PER_REV2 144000 +#define COUNTS_PER_REV3 144000 +#define COUNTS_PER_REV4 144000 +#define WHEEL_DIAMETER 0.152 +#define LR_WHEELS_DISTANCE 0.271 +#define PWM_BITS 8 +#define PWM_FREQUENCY 20000 + +/// ENCODER PINS +#define MOTOR1_ENCODER_A 14 +#define MOTOR1_ENCODER_B 15 +#define MOTOR1_ENCODER_INV false + +#define MOTOR2_ENCODER_A 11 +#define MOTOR2_ENCODER_B 12 +#define MOTOR2_ENCODER_INV false + +#define MOTOR3_ENCODER_A 17 +#define MOTOR3_ENCODER_B 16 +#define MOTOR3_ENCODER_INV true + +#define MOTOR4_ENCODER_A 9 +#define MOTOR4_ENCODER_B 10 +#define MOTOR4_ENCODER_INV false + +// Motor Pins +#define MOTOR1_PWM 21 +#define MOTOR1_IN_A 20 +#define MOTOR1_IN_B -1 +#define MOTOR1_INV false + +#define MOTOR2_PWM 5 +#define MOTOR2_IN_A 6 +#define MOTOR2_IN_B -1 +#define MOTOR2_INV true + +#define MOTOR3_PWM 22 +#define MOTOR3_IN_A 23 +#define MOTOR3_IN_B -1 +#define MOTOR3_INV false + +#define MOTOR4_PWM 4 +#define MOTOR4_IN_A 3 +#define MOTOR4_IN_B -1 +#define MOTOR4_INV false + +#define PWM_MAX pow(2, PWM_BITS) - 1 +#define PWM_MIN -PWM_MAX + +#endif \ No newline at end of file diff --git a/config/custom/square_config.h b/config/custom/square_config.h new file mode 100644 index 0000000..19891c3 --- /dev/null +++ b/config/custom/square_config.h @@ -0,0 +1,84 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SQUARE_CONFIG_H +#define SQUARE_CONFIG_H + +#define LED_PIN 13 + +#define LINO_BASE DIFFERENTIAL_DRIVE + +#define USE_GENERIC_2_IN_MOTOR_DRIVER +#define USE_GY85_IMU + +#define K_P 20. +#define K_I 0.8 +#define K_D 5. + +#define MOTOR_MAX_RPM 100 +#define MAX_RPM_RATIO 0.8 +#define MOTOR_OPERATING_VOLTAGE 12 +#define MOTOR_POWER_MAX_VOLTAGE 12 +#define MOTOR_POWER_MEASURED_VOLTAGE 11.67 +#define COUNTS_PER_REV1 2513 +#define COUNTS_PER_REV2 2580 +#define COUNTS_PER_REV3 2421 +#define COUNTS_PER_REV4 2501 +#define WHEEL_DIAMETER 0.09 +#define LR_WHEELS_DISTANCE 0.24 +#define PWM_BITS 10 +#define PWM_FREQUENCY 20000 + +/// ENCODER PINS +#define MOTOR1_ENCODER_A 14 +#define MOTOR1_ENCODER_B 15 +#define MOTOR1_ENCODER_INV false + +#define MOTOR2_ENCODER_A 11 +#define MOTOR2_ENCODER_B 12 +#define MOTOR2_ENCODER_INV false + +#define MOTOR3_ENCODER_A 17 +#define MOTOR3_ENCODER_B 16 +#define MOTOR3_ENCODER_INV true + +#define MOTOR4_ENCODER_A 9 +#define MOTOR4_ENCODER_B 10 +#define MOTOR4_ENCODER_INV false + +// Motor Pins +#define MOTOR1_PWM 1 +#define MOTOR1_IN_A 20 +#define MOTOR1_IN_B 21 +#define MOTOR1_INV false + +#define MOTOR2_PWM 5 +#define MOTOR2_IN_A 6 +#define MOTOR2_IN_B 8 +#define MOTOR2_INV true + +#define MOTOR3_PWM 22 +#define MOTOR3_IN_A 23 +#define MOTOR3_IN_B 0 +#define MOTOR3_INV false + +#define MOTOR4_PWM 4 +#define MOTOR4_IN_A 3 +#define MOTOR4_IN_B 2 +#define MOTOR4_INV false + +#define PWM_MAX pow(2, PWM_BITS) - 1 +#define PWM_MIN -PWM_MAX + +#endif diff --git a/config/lino_base_config.h b/config/lino_base_config.h new file mode 100644 index 0000000..6016c50 --- /dev/null +++ b/config/lino_base_config.h @@ -0,0 +1,176 @@ +// Copyright (c) 2021 Juan Miguel Jimeno +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LINO_BASE_CONFIG_H +#define LINO_BASE_CONFIG_H + +#define LED_PIN 13 //LED_PIN LED_BUILTIN //13 //used for debugging status + +//uncomment the base you're building +#define LINO_BASE DIFFERENTIAL_DRIVE // 2WD and Tracked robot w/ 2 motors +// #define LINO_BASE SKID_STEER // 4WD robot +// #define LINO_BASE MECANUM // Mecanum drive robot + +//uncomment the motor driver you're using +#define USE_GENERIC_2_IN_MOTOR_DRIVER // Motor drivers with 2 Direction Pins(INA, INB) and 1 PWM(ENABLE) pin ie. L298, L293, VNH5019 +// #define USE_GENERIC_1_IN_MOTOR_DRIVER // Motor drivers with 1 Direction Pin(INA) and 1 PWM(ENABLE) pin. +// #define USE_BTS7960_MOTOR_DRIVER // BTS7970 Motor Driver +// #define USE_ESC_MOTOR_DRIVER // Motor ESC for brushless motors + +//uncomment the IMU you're using +// #define USE_GY85_IMU +// #define USE_MPU6050_IMU +// #define USE_MPU9150_IMU +// #define USE_MPU9250_IMU +#define USE_MPU9250_WE_IMU +//#define USE_FAKE_IMU + +#define K_P 0.6 // P constant +#define K_I 0.8 // I constant +#define K_D 0.5 // D constant + +/* +ROBOT ORIENTATION + FRONT + MOTOR1 MOTOR2 (2WD/ACKERMANN) + MOTOR3 MOTOR4 (4WD/MECANUM) + BACK +*/ + +//define your robot' specs here +#define MOTOR_MAX_RPM 140 // motor's max RPM +#define MAX_RPM_RATIO 0.85 // max RPM allowed for each MAX_RPM_ALLOWED = MOTOR_MAX_RPM * MAX_RPM_RATIO +#define MOTOR_OPERATING_VOLTAGE 24 // motor's operating voltage (used to calculate max RPM) +#define MOTOR_POWER_MAX_VOLTAGE 12 // max voltage of the motor's power source (used to calculate max RPM) +#define MOTOR_POWER_MEASURED_VOLTAGE 12 // current voltage reading of the power connected to the motor (used for calibration) +#define COUNTS_PER_REV1 144000 // wheel1 encoder's no of ticks per rev +#define COUNTS_PER_REV2 144000 // wheel2 encoder's no of ticks per rev +#define COUNTS_PER_REV3 144000 // wheel3 encoder's no of ticks per rev +#define COUNTS_PER_REV4 144000 // wheel4 encoder's no of ticks per rev +#define WHEEL_DIAMETER 0.152 // wheel's diameter in meters +#define LR_WHEELS_DISTANCE 0.271 // distance between left and right wheels +#define PWM_BITS 10 // PWM Resolution of the microcontroller +#define PWM_FREQUENCY 20000 // PWM Frequency + +// INVERT ENCODER COUNTS +#define MOTOR1_ENCODER_INV false +#define MOTOR2_ENCODER_INV false +#define MOTOR3_ENCODER_INV false +#define MOTOR4_ENCODER_INV false + +// INVERT MOTOR DIRECTIONS +#define MOTOR1_INV false +#define MOTOR2_INV false +#define MOTOR3_INV false +#define MOTOR4_INV false + +// ENCODER PINS +#define MOTOR1_ENCODER_A 14 +#define MOTOR1_ENCODER_B 15 + +#define MOTOR2_ENCODER_A 11 +#define MOTOR2_ENCODER_B 12 + +#define MOTOR3_ENCODER_A 17 +#define MOTOR3_ENCODER_B 16 + +#define MOTOR4_ENCODER_A 9 +#define MOTOR4_ENCODER_B 10 + +// MOTOR PINS +#ifdef USE_GENERIC_2_IN_MOTOR_DRIVER + #define MOTOR1_PWM 21 //Pin no 21 is not a PWM pin on Teensy 4.x, you can swap it with pin no 1 instead. + #define MOTOR1_IN_A 20 + #define MOTOR1_IN_B 1 + + #define MOTOR2_PWM 5 + #define MOTOR2_IN_A 6 + #define MOTOR2_IN_B 8 + + #define MOTOR3_PWM 22 + #define MOTOR3_IN_A 23 + #define MOTOR3_IN_B 0 + + #define MOTOR4_PWM 4 + #define MOTOR4_IN_A 3 + #define MOTOR4_IN_B 2 + + #define PWM_MAX pow(2, PWM_BITS) - 1 + #define PWM_MIN -PWM_MAX +#endif + +#ifdef USE_GENERIC_1_IN_MOTOR_DRIVER + #define MOTOR1_PWM 21 //Pin no 21 is not a PWM pin on Teensy 4.x, you can use pin no 1 instead. + #define MOTOR1_IN_A 20 + #define MOTOR1_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR2_PWM 5 + #define MOTOR2_IN_A 6 + #define MOTOR2_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR3_PWM 22 + #define MOTOR3_IN_A 23 + #define MOTOR3_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR4_PWM 4 + #define MOTOR4_IN_A 3 + #define MOTOR4_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define PWM_MAX pow(2, PWM_BITS) - 1 + #define PWM_MIN -PWM_MAX +#endif + +#ifdef USE_BTS7960_MOTOR_DRIVER + #define MOTOR1_PWM -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR1_IN_A 21 // Pin no 21 is not a PWM pin on Teensy 4.x, you can use pin no 1 instead. + #define MOTOR1_IN_B 20 // Pin no 20 is not a PWM pin on Teensy 4.x, you can use pin no 0 instead. + + #define MOTOR2_PWM -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR2_IN_A 5 + #define MOTOR2_IN_B 6 + + #define MOTOR3_PWM -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR3_IN_A 22 + #define MOTOR3_IN_B 23 + + #define MOTOR4_PWM -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR4_IN_A 4 + #define MOTOR4_IN_B 3 + + #define PWM_MAX pow(2, PWM_BITS) - 1 + #define PWM_MIN -PWM_MAX +#endif + +#ifdef USE_ESC_MOTOR_DRIVER + #define MOTOR1_PWM 21 //Pin no 21 is not a PWM pin on Teensy 4.x. You can use pin no 1 instead. + #define MOTOR1_IN_A -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR1_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR2_PWM 5 + #define MOTOR2_IN_A -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR2_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR3_PWM 22 + #define MOTOR3_IN_A -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR3_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define MOTOR4_PWM 4 + #define MOTOR4_IN_A -1 //DON'T TOUCH THIS! This is just a placeholder + #define MOTOR4_IN_B -1 //DON'T TOUCH THIS! This is just a placeholder + + #define PWM_MAX 400 + #define PWM_MIN -PWM_MAX +#endif + +#endif diff --git a/firmware/.gitignore b/firmware/.gitignore new file mode 100644 index 0000000..89cc49c --- /dev/null +++ b/firmware/.gitignore @@ -0,0 +1,5 @@ +.pio +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json +.vscode/ipch diff --git a/firmware/.vscode/extensions.json b/firmware/.vscode/extensions.json new file mode 100644 index 0000000..080e70d --- /dev/null +++ b/firmware/.vscode/extensions.json @@ -0,0 +1,10 @@ +{ + // See http://go.microsoft.com/fwlink/?LinkId=827846 + // for the documentation about the extensions.json format + "recommendations": [ + "platformio.platformio-ide" + ], + "unwantedRecommendations": [ + "ms-vscode.cpptools-extension-pack" + ] +} diff --git a/firmware/.vscode/settings.json b/firmware/.vscode/settings.json new file mode 100644 index 0000000..593784e --- /dev/null +++ b/firmware/.vscode/settings.json @@ -0,0 +1,10 @@ +{ + "python.autoComplete.extraPaths": [ + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ], + "python.analysis.extraPaths": [ + "/opt/ros/humble/lib/python3.10/site-packages", + "/opt/ros/humble/local/lib/python3.10/dist-packages" + ] +} \ No newline at end of file diff --git a/firmware/include/README b/firmware/include/README new file mode 100644 index 0000000..194dcd4 --- /dev/null +++ b/firmware/include/README @@ -0,0 +1,39 @@ + +This directory is intended for project header files. + +A header file is a file containing C declarations and macro definitions +to be shared between several project source files. You request the use of a +header file in your project source file (C, C++, etc) located in `src` folder +by including it, with the C preprocessing directive `#include'. + +```src/main.c + +#include "header.h" + +int main (void) +{ + ... +} +``` + +Including a header file produces the same results as copying the header file +into each source file that needs it. Such copying would be time-consuming +and error-prone. With a header file, the related declarations appear +in only one place. If they need to be changed, they can be changed in one +place, and programs that include the header file will automatically use the +new version when next recompiled. The header file eliminates the labor of +finding and changing all the copies as well as the risk that a failure to +find one copy will result in inconsistencies within a program. + +In C, the usual convention is to give header files names that end with `.h'. +It is most portable to use only letters, digits, dashes, and underscores in +header file names, and at most one dot. + +Read more about using header files in official GCC documentation: + +* Include Syntax +* Include Operation +* Once-Only Headers +* Computed Includes + +https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html diff --git a/firmware/lib/encoder/encoder.cpp b/firmware/lib/encoder/encoder.cpp new file mode 100644 index 0000000..aee0e87 --- /dev/null +++ b/firmware/lib/encoder/encoder.cpp @@ -0,0 +1,10 @@ + +// #include "encoder.h" + +// // Yes, all the code is in the header file, to provide the user +// // configure options with #define (before they include it), and +// // to facilitate some crafty optimizations! + +// Encoder_internal_state_t * Encoder::interruptArgs[]; + + diff --git a/firmware/lib/encoder/encoder.h b/firmware/lib/encoder/encoder.h new file mode 100644 index 0000000..d47521d --- /dev/null +++ b/firmware/lib/encoder/encoder.h @@ -0,0 +1,1005 @@ +// /* Encoder Library, for measuring quadrature encoded signals +// * http://www.pjrc.com/teensy/td_libs_Encoder.html +// * Copyright (c) 2011,2013 PJRC.COM, LLC - Paul Stoffregen +// * +// * Version 1.2 - fix -2 bug in C-only code +// * Version 1.1 - expand to support boards with up to 60 interrupts +// * Version 1.0 - initial release +// * +// * 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 Encoder_h_ +// #define Encoder_h_ + +// #if defined(ARDUINO) && ARDUINO >= 100 +// #include "Arduino.h" +// #elif defined(WIRING) +// #include "Wiring.h" +// #else +// #include "WProgram.h" +// #include "pins_arduino.h" +// #endif + +// #include "utility/direct_pin_read.h" + +// #if defined(ENCODER_USE_INTERRUPTS) || !defined(ENCODER_DO_NOT_USE_INTERRUPTS) +// #define ENCODER_USE_INTERRUPTS +// #define ENCODER_ARGLIST_SIZE CORE_NUM_INTERRUPT +// #include "utility/interrupt_pins.h" +// #ifdef ENCODER_OPTIMIZE_INTERRUPTS +// #include "utility/interrupt_config.h" +// #endif +// #else +// #define ENCODER_ARGLIST_SIZE 0 +// #endif + +// // Use ICACHE_RAM_ATTR for ISRs to prevent ESP8266 resets +// #if defined(ESP8266) || defined(ESP32) +// #define ENCODER_ISR_ATTR ICACHE_RAM_ATTR +// #else +// #define ENCODER_ISR_ATTR +// #endif + + + +// // All the data needed by interrupts is consolidated into this ugly struct +// // to facilitate assembly language optimizing of the speed critical update. +// // The assembly code uses auto-incrementing addressing modes, so the struct +// // must remain in exactly this order. +// typedef struct { +// volatile IO_REG_TYPE * pin1_register; +// volatile IO_REG_TYPE * pin2_register; +// IO_REG_TYPE pin1_bitmask; +// IO_REG_TYPE pin2_bitmask; +// uint8_t state; +// int32_t position; +// } Encoder_internal_state_t; + +// class Encoder +// { +// public: +// Encoder(uint8_t pin1, uint8_t pin2, int counts_per_rev, bool invert=false) { +// uint8_t temp_pin = pin1; +// if(invert) +// { +// pin1 = pin2; +// pin2 = temp_pin; +// } +// #ifdef INPUT_PULLUP +// pinMode(pin1, INPUT_PULLUP); +// pinMode(pin2, INPUT_PULLUP); +// #else +// pinMode(pin1, INPUT); +// digitalWrite(pin1, HIGH); +// pinMode(pin2, INPUT); +// digitalWrite(pin2, HIGH); +// #endif + +// counts_per_rev_ = counts_per_rev; + +// encoder.pin1_register = PIN_TO_BASEREG(pin1); +// encoder.pin1_bitmask = PIN_TO_BITMASK(pin1); +// encoder.pin2_register = PIN_TO_BASEREG(pin2); +// encoder.pin2_bitmask = PIN_TO_BITMASK(pin2); +// encoder.position = 0; +// // allow time for a passive R-C filter to charge +// // through the pullup resistors, before reading +// // the initial state +// delayMicroseconds(2000); +// uint8_t s = 0; +// if (DIRECT_PIN_READ(encoder.pin1_register, encoder.pin1_bitmask)) s |= 1; +// if (DIRECT_PIN_READ(encoder.pin2_register, encoder.pin2_bitmask)) s |= 2; +// encoder.state = s; +// #ifdef ENCODER_USE_INTERRUPTS +// interrupts_in_use = attach_interrupt(pin1, &encoder); +// interrupts_in_use += attach_interrupt(pin2, &encoder); +// #endif +// //update_finishup(); // to force linker to include the code (does not work) +// } + + +// #ifdef ENCODER_USE_INTERRUPTS +// inline int32_t read() { +// if (interrupts_in_use < 2) { +// noInterrupts(); +// update(&encoder); +// } else { +// noInterrupts(); +// } +// int32_t ret = encoder.position; +// interrupts(); +// return ret; +// } +// inline int32_t readAndReset() { +// if (interrupts_in_use < 2) { +// noInterrupts(); +// update(&encoder); +// } else { +// noInterrupts(); +// } +// int32_t ret = encoder.position; +// encoder.position = 0; +// interrupts(); +// return ret; +// } +// inline void write(int32_t p) { +// noInterrupts(); +// encoder.position = p; +// interrupts(); +// } +// #else +// inline int32_t read() { +// update(&encoder); +// return encoder.position; +// } +// inline int32_t readAndReset() { +// update(&encoder); +// int32_t ret = encoder.position; +// encoder.position = 0; +// return ret; +// } +// inline void write(int32_t p) { +// encoder.position = p; +// } +// #endif +// float getRPM(){ +// long encoder_ticks = read(); +// //this function calculates the motor's RPM based on encoder ticks and delta time +// unsigned long current_time = micros(); +// unsigned long dt = current_time - prev_update_time_; + +// //convert the time from milliseconds to minutes +// double dtm = (double)dt / 60000000; +// double delta_ticks = encoder_ticks - prev_encoder_ticks_; + +// //calculate wheel's speed (RPM) +// prev_update_time_ = current_time; +// prev_encoder_ticks_ = encoder_ticks; + +// return ((delta_ticks / counts_per_rev_) / dtm); +// } + +// private: +// int counts_per_rev_; +// unsigned long prev_update_time_; +// long prev_encoder_ticks_; +// Encoder_internal_state_t encoder; +// #ifdef ENCODER_USE_INTERRUPTS +// uint8_t interrupts_in_use; +// #endif +// public: +// static Encoder_internal_state_t * interruptArgs[ENCODER_ARGLIST_SIZE]; + +// // _______ _______ +// // Pin1 ______| |_______| |______ Pin1 +// // negative <--- _______ _______ __ --> positive +// // Pin2 __| |_______| |_______| Pin2 + +// // new new old old +// // pin2 pin1 pin2 pin1 Result +// // ---- ---- ---- ---- ------ +// // 0 0 0 0 no movement +// // 0 0 0 1 +1 +// // 0 0 1 0 -1 +// // 0 0 1 1 +2 (assume pin1 edges only) +// // 0 1 0 0 -1 +// // 0 1 0 1 no movement +// // 0 1 1 0 -2 (assume pin1 edges only) +// // 0 1 1 1 +1 +// // 1 0 0 0 +1 +// // 1 0 0 1 -2 (assume pin1 edges only) +// // 1 0 1 0 no movement +// // 1 0 1 1 -1 +// // 1 1 0 0 +2 (assume pin1 edges only) +// // 1 1 0 1 -1 +// // 1 1 1 0 +1 +// // 1 1 1 1 no movement +// /* +// // Simple, easy-to-read "documentation" version :-) +// // +// void update(void) { +// uint8_t s = state & 3; +// if (digitalRead(pin1)) s |= 4; +// if (digitalRead(pin2)) s |= 8; +// switch (s) { +// case 0: case 5: case 10: case 15: +// break; +// case 1: case 7: case 8: case 14: +// position++; break; +// case 2: case 4: case 11: case 13: +// position--; break; +// case 3: case 12: +// position += 2; break; +// default: +// position -= 2; break; +// } +// state = (s >> 2); +// } +// */ + +// public: +// // update() is not meant to be called from outside Encoder, +// // but it is public to allow static interrupt routines. +// // DO NOT call update() directly from sketches. +// static void update(Encoder_internal_state_t *arg) { +// #if defined(__AVR__) +// // The compiler believes this is just 1 line of code, so +// // it will inline this function into each interrupt +// // handler. That's a tiny bit faster, but grows the code. +// // Especially when used with ENCODER_OPTIMIZE_INTERRUPTS, +// // the inline nature allows the ISR prologue and epilogue +// // to only save/restore necessary registers, for very nice +// // speed increase. +// asm volatile ( +// "ld r30, X+" "\n\t" +// "ld r31, X+" "\n\t" +// "ld r24, Z" "\n\t" // r24 = pin1 input +// "ld r30, X+" "\n\t" +// "ld r31, X+" "\n\t" +// "ld r25, Z" "\n\t" // r25 = pin2 input +// "ld r30, X+" "\n\t" // r30 = pin1 mask +// "ld r31, X+" "\n\t" // r31 = pin2 mask +// "ld r22, X" "\n\t" // r22 = state +// "andi r22, 3" "\n\t" +// "and r24, r30" "\n\t" +// "breq L%=1" "\n\t" // if (pin1) +// "ori r22, 4" "\n\t" // state |= 4 +// "L%=1:" "and r25, r31" "\n\t" +// "breq L%=2" "\n\t" // if (pin2) +// "ori r22, 8" "\n\t" // state |= 8 +// "L%=2:" "ldi r30, lo8(pm(L%=table))" "\n\t" +// "ldi r31, hi8(pm(L%=table))" "\n\t" +// "add r30, r22" "\n\t" +// "adc r31, __zero_reg__" "\n\t" +// "asr r22" "\n\t" +// "asr r22" "\n\t" +// "st X+, r22" "\n\t" // store new state +// "ld r22, X+" "\n\t" +// "ld r23, X+" "\n\t" +// "ld r24, X+" "\n\t" +// "ld r25, X+" "\n\t" +// "ijmp" "\n\t" // jumps to update_finishup() +// // TODO move this table to another static function, +// // so it doesn't get needlessly duplicated. Easier +// // said than done, due to linker issues and inlining +// "L%=table:" "\n\t" +// "rjmp L%=end" "\n\t" // 0 +// "rjmp L%=plus1" "\n\t" // 1 +// "rjmp L%=minus1" "\n\t" // 2 +// "rjmp L%=plus2" "\n\t" // 3 +// "rjmp L%=minus1" "\n\t" // 4 +// "rjmp L%=end" "\n\t" // 5 +// "rjmp L%=minus2" "\n\t" // 6 +// "rjmp L%=plus1" "\n\t" // 7 +// "rjmp L%=plus1" "\n\t" // 8 +// "rjmp L%=minus2" "\n\t" // 9 +// "rjmp L%=end" "\n\t" // 10 +// "rjmp L%=minus1" "\n\t" // 11 +// "rjmp L%=plus2" "\n\t" // 12 +// "rjmp L%=minus1" "\n\t" // 13 +// "rjmp L%=plus1" "\n\t" // 14 +// "rjmp L%=end" "\n\t" // 15 +// "L%=minus2:" "\n\t" +// "subi r22, 2" "\n\t" +// "sbci r23, 0" "\n\t" +// "sbci r24, 0" "\n\t" +// "sbci r25, 0" "\n\t" +// "rjmp L%=store" "\n\t" +// "L%=minus1:" "\n\t" +// "subi r22, 1" "\n\t" +// "sbci r23, 0" "\n\t" +// "sbci r24, 0" "\n\t" +// "sbci r25, 0" "\n\t" +// "rjmp L%=store" "\n\t" +// "L%=plus2:" "\n\t" +// "subi r22, 254" "\n\t" +// "rjmp L%=z" "\n\t" +// "L%=plus1:" "\n\t" +// "subi r22, 255" "\n\t" +// "L%=z:" "sbci r23, 255" "\n\t" +// "sbci r24, 255" "\n\t" +// "sbci r25, 255" "\n\t" +// "L%=store:" "\n\t" +// "st -X, r25" "\n\t" +// "st -X, r24" "\n\t" +// "st -X, r23" "\n\t" +// "st -X, r22" "\n\t" +// "L%=end:" "\n" +// : : "x" (arg) : "r22", "r23", "r24", "r25", "r30", "r31"); +// #else +// uint8_t p1val = DIRECT_PIN_READ(arg->pin1_register, arg->pin1_bitmask); +// uint8_t p2val = DIRECT_PIN_READ(arg->pin2_register, arg->pin2_bitmask); +// uint8_t state = arg->state & 3; +// if (p1val) state |= 4; +// if (p2val) state |= 8; +// arg->state = (state >> 2); +// switch (state) { +// case 1: case 7: case 8: case 14: +// arg->position++; +// return; +// case 2: case 4: case 11: case 13: +// arg->position--; +// return; +// case 3: case 12: +// arg->position += 2; +// return; +// case 6: case 9: +// arg->position -= 2; +// return; +// } +// #endif +// } +// private: +// /* +// #if defined(__AVR__) +// // TODO: this must be a no inline function +// // even noinline does not seem to solve difficult +// // problems with this. Oh well, it was only meant +// // to shrink code size - there's no performance +// // improvement in this, only code size reduction. +// __attribute__((noinline)) void update_finishup(void) { +// asm volatile ( +// "ldi r30, lo8(pm(Ltable))" "\n\t" +// "ldi r31, hi8(pm(Ltable))" "\n\t" +// "Ltable:" "\n\t" +// "rjmp L%=end" "\n\t" // 0 +// "rjmp L%=plus1" "\n\t" // 1 +// "rjmp L%=minus1" "\n\t" // 2 +// "rjmp L%=plus2" "\n\t" // 3 +// "rjmp L%=minus1" "\n\t" // 4 +// "rjmp L%=end" "\n\t" // 5 +// "rjmp L%=minus2" "\n\t" // 6 +// "rjmp L%=plus1" "\n\t" // 7 +// "rjmp L%=plus1" "\n\t" // 8 +// "rjmp L%=minus2" "\n\t" // 9 +// "rjmp L%=end" "\n\t" // 10 +// "rjmp L%=minus1" "\n\t" // 11 +// "rjmp L%=plus2" "\n\t" // 12 +// "rjmp L%=minus1" "\n\t" // 13 +// "rjmp L%=plus1" "\n\t" // 14 +// "rjmp L%=end" "\n\t" // 15 +// "L%=minus2:" "\n\t" +// "subi r22, 2" "\n\t" +// "sbci r23, 0" "\n\t" +// "sbci r24, 0" "\n\t" +// "sbci r25, 0" "\n\t" +// "rjmp L%=store" "\n\t" +// "L%=minus1:" "\n\t" +// "subi r22, 1" "\n\t" +// "sbci r23, 0" "\n\t" +// "sbci r24, 0" "\n\t" +// "sbci r25, 0" "\n\t" +// "rjmp L%=store" "\n\t" +// "L%=plus2:" "\n\t" +// "subi r22, 254" "\n\t" +// "rjmp L%=z" "\n\t" +// "L%=plus1:" "\n\t" +// "subi r22, 255" "\n\t" +// "L%=z:" "sbci r23, 255" "\n\t" +// "sbci r24, 255" "\n\t" +// "sbci r25, 255" "\n\t" +// "L%=store:" "\n\t" +// "st -X, r25" "\n\t" +// "st -X, r24" "\n\t" +// "st -X, r23" "\n\t" +// "st -X, r22" "\n\t" +// "L%=end:" "\n" +// : : : "r22", "r23", "r24", "r25", "r30", "r31"); +// } +// #endif +// */ + + +// #ifdef ENCODER_USE_INTERRUPTS +// // this giant function is an unfortunate consequence of Arduino's +// // attachInterrupt function not supporting any way to pass a pointer +// // or other context to the attached function. +// static uint8_t attach_interrupt(uint8_t pin, Encoder_internal_state_t *state) { +// switch (pin) { +// #ifdef CORE_INT0_PIN +// case CORE_INT0_PIN: +// interruptArgs[0] = state; +// attachInterrupt(0, isr0, CHANGE); +// break; +// #endif +// #ifdef CORE_INT1_PIN +// case CORE_INT1_PIN: +// interruptArgs[1] = state; +// attachInterrupt(1, isr1, CHANGE); +// break; +// #endif +// #ifdef CORE_INT2_PIN +// case CORE_INT2_PIN: +// interruptArgs[2] = state; +// attachInterrupt(2, isr2, CHANGE); +// break; +// #endif +// #ifdef CORE_INT3_PIN +// case CORE_INT3_PIN: +// interruptArgs[3] = state; +// attachInterrupt(3, isr3, CHANGE); +// break; +// #endif +// #ifdef CORE_INT4_PIN +// case CORE_INT4_PIN: +// interruptArgs[4] = state; +// attachInterrupt(4, isr4, CHANGE); +// break; +// #endif +// #ifdef CORE_INT5_PIN +// case CORE_INT5_PIN: +// interruptArgs[5] = state; +// attachInterrupt(5, isr5, CHANGE); +// break; +// #endif +// #ifdef CORE_INT6_PIN +// case CORE_INT6_PIN: +// interruptArgs[6] = state; +// attachInterrupt(6, isr6, CHANGE); +// break; +// #endif +// #ifdef CORE_INT7_PIN +// case CORE_INT7_PIN: +// interruptArgs[7] = state; +// attachInterrupt(7, isr7, CHANGE); +// break; +// #endif +// #ifdef CORE_INT8_PIN +// case CORE_INT8_PIN: +// interruptArgs[8] = state; +// attachInterrupt(8, isr8, CHANGE); +// break; +// #endif +// #ifdef CORE_INT9_PIN +// case CORE_INT9_PIN: +// interruptArgs[9] = state; +// attachInterrupt(9, isr9, CHANGE); +// break; +// #endif +// #ifdef CORE_INT10_PIN +// case CORE_INT10_PIN: +// interruptArgs[10] = state; +// attachInterrupt(10, isr10, CHANGE); +// break; +// #endif +// #ifdef CORE_INT11_PIN +// case CORE_INT11_PIN: +// interruptArgs[11] = state; +// attachInterrupt(11, isr11, CHANGE); +// break; +// #endif +// #ifdef CORE_INT12_PIN +// case CORE_INT12_PIN: +// interruptArgs[12] = state; +// attachInterrupt(12, isr12, CHANGE); +// break; +// #endif +// #ifdef CORE_INT13_PIN +// case CORE_INT13_PIN: +// interruptArgs[13] = state; +// attachInterrupt(13, isr13, CHANGE); +// break; +// #endif +// #ifdef CORE_INT14_PIN +// case CORE_INT14_PIN: +// interruptArgs[14] = state; +// attachInterrupt(14, isr14, CHANGE); +// break; +// #endif +// #ifdef CORE_INT15_PIN +// case CORE_INT15_PIN: +// interruptArgs[15] = state; +// attachInterrupt(15, isr15, CHANGE); +// break; +// #endif +// #ifdef CORE_INT16_PIN +// case CORE_INT16_PIN: +// interruptArgs[16] = state; +// attachInterrupt(16, isr16, CHANGE); +// break; +// #endif +// #ifdef CORE_INT17_PIN +// case CORE_INT17_PIN: +// interruptArgs[17] = state; +// attachInterrupt(17, isr17, CHANGE); +// break; +// #endif +// #ifdef CORE_INT18_PIN +// case CORE_INT18_PIN: +// interruptArgs[18] = state; +// attachInterrupt(18, isr18, CHANGE); +// break; +// #endif +// #ifdef CORE_INT19_PIN +// case CORE_INT19_PIN: +// interruptArgs[19] = state; +// attachInterrupt(19, isr19, CHANGE); +// break; +// #endif +// #ifdef CORE_INT20_PIN +// case CORE_INT20_PIN: +// interruptArgs[20] = state; +// attachInterrupt(20, isr20, CHANGE); +// break; +// #endif +// #ifdef CORE_INT21_PIN +// case CORE_INT21_PIN: +// interruptArgs[21] = state; +// attachInterrupt(21, isr21, CHANGE); +// break; +// #endif +// #ifdef CORE_INT22_PIN +// case CORE_INT22_PIN: +// interruptArgs[22] = state; +// attachInterrupt(22, isr22, CHANGE); +// break; +// #endif +// #ifdef CORE_INT23_PIN +// case CORE_INT23_PIN: +// interruptArgs[23] = state; +// attachInterrupt(23, isr23, CHANGE); +// break; +// #endif +// #ifdef CORE_INT24_PIN +// case CORE_INT24_PIN: +// interruptArgs[24] = state; +// attachInterrupt(24, isr24, CHANGE); +// break; +// #endif +// #ifdef CORE_INT25_PIN +// case CORE_INT25_PIN: +// interruptArgs[25] = state; +// attachInterrupt(25, isr25, CHANGE); +// break; +// #endif +// #ifdef CORE_INT26_PIN +// case CORE_INT26_PIN: +// interruptArgs[26] = state; +// attachInterrupt(26, isr26, CHANGE); +// break; +// #endif +// #ifdef CORE_INT27_PIN +// case CORE_INT27_PIN: +// interruptArgs[27] = state; +// attachInterrupt(27, isr27, CHANGE); +// break; +// #endif +// #ifdef CORE_INT28_PIN +// case CORE_INT28_PIN: +// interruptArgs[28] = state; +// attachInterrupt(28, isr28, CHANGE); +// break; +// #endif +// #ifdef CORE_INT29_PIN +// case CORE_INT29_PIN: +// interruptArgs[29] = state; +// attachInterrupt(29, isr29, CHANGE); +// break; +// #endif + +// #ifdef CORE_INT30_PIN +// case CORE_INT30_PIN: +// interruptArgs[30] = state; +// attachInterrupt(30, isr30, CHANGE); +// break; +// #endif +// #ifdef CORE_INT31_PIN +// case CORE_INT31_PIN: +// interruptArgs[31] = state; +// attachInterrupt(31, isr31, CHANGE); +// break; +// #endif +// #ifdef CORE_INT32_PIN +// case CORE_INT32_PIN: +// interruptArgs[32] = state; +// attachInterrupt(32, isr32, CHANGE); +// break; +// #endif +// #ifdef CORE_INT33_PIN +// case CORE_INT33_PIN: +// interruptArgs[33] = state; +// attachInterrupt(33, isr33, CHANGE); +// break; +// #endif +// #ifdef CORE_INT34_PIN +// case CORE_INT34_PIN: +// interruptArgs[34] = state; +// attachInterrupt(34, isr34, CHANGE); +// break; +// #endif +// #ifdef CORE_INT35_PIN +// case CORE_INT35_PIN: +// interruptArgs[35] = state; +// attachInterrupt(35, isr35, CHANGE); +// break; +// #endif +// #ifdef CORE_INT36_PIN +// case CORE_INT36_PIN: +// interruptArgs[36] = state; +// attachInterrupt(36, isr36, CHANGE); +// break; +// #endif +// #ifdef CORE_INT37_PIN +// case CORE_INT37_PIN: +// interruptArgs[37] = state; +// attachInterrupt(37, isr37, CHANGE); +// break; +// #endif +// #ifdef CORE_INT38_PIN +// case CORE_INT38_PIN: +// interruptArgs[38] = state; +// attachInterrupt(38, isr38, CHANGE); +// break; +// #endif +// #ifdef CORE_INT39_PIN +// case CORE_INT39_PIN: +// interruptArgs[39] = state; +// attachInterrupt(39, isr39, CHANGE); +// break; +// #endif +// #ifdef CORE_INT40_PIN +// case CORE_INT40_PIN: +// interruptArgs[40] = state; +// attachInterrupt(40, isr40, CHANGE); +// break; +// #endif +// #ifdef CORE_INT41_PIN +// case CORE_INT41_PIN: +// interruptArgs[41] = state; +// attachInterrupt(41, isr41, CHANGE); +// break; +// #endif +// #ifdef CORE_INT42_PIN +// case CORE_INT42_PIN: +// interruptArgs[42] = state; +// attachInterrupt(42, isr42, CHANGE); +// break; +// #endif +// #ifdef CORE_INT43_PIN +// case CORE_INT43_PIN: +// interruptArgs[43] = state; +// attachInterrupt(43, isr43, CHANGE); +// break; +// #endif +// #ifdef CORE_INT44_PIN +// case CORE_INT44_PIN: +// interruptArgs[44] = state; +// attachInterrupt(44, isr44, CHANGE); +// break; +// #endif +// #ifdef CORE_INT45_PIN +// case CORE_INT45_PIN: +// interruptArgs[45] = state; +// attachInterrupt(45, isr45, CHANGE); +// break; +// #endif +// #ifdef CORE_INT46_PIN +// case CORE_INT46_PIN: +// interruptArgs[46] = state; +// attachInterrupt(46, isr46, CHANGE); +// break; +// #endif +// #ifdef CORE_INT47_PIN +// case CORE_INT47_PIN: +// interruptArgs[47] = state; +// attachInterrupt(47, isr47, CHANGE); +// break; +// #endif +// #ifdef CORE_INT48_PIN +// case CORE_INT48_PIN: +// interruptArgs[48] = state; +// attachInterrupt(48, isr48, CHANGE); +// break; +// #endif +// #ifdef CORE_INT49_PIN +// case CORE_INT49_PIN: +// interruptArgs[49] = state; +// attachInterrupt(49, isr49, CHANGE); +// break; +// #endif +// #ifdef CORE_INT50_PIN +// case CORE_INT50_PIN: +// interruptArgs[50] = state; +// attachInterrupt(50, isr50, CHANGE); +// break; +// #endif +// #ifdef CORE_INT51_PIN +// case CORE_INT51_PIN: +// interruptArgs[51] = state; +// attachInterrupt(51, isr51, CHANGE); +// break; +// #endif +// #ifdef CORE_INT52_PIN +// case CORE_INT52_PIN: +// interruptArgs[52] = state; +// attachInterrupt(52, isr52, CHANGE); +// break; +// #endif +// #ifdef CORE_INT53_PIN +// case CORE_INT53_PIN: +// interruptArgs[53] = state; +// attachInterrupt(53, isr53, CHANGE); +// break; +// #endif +// #ifdef CORE_INT54_PIN +// case CORE_INT54_PIN: +// interruptArgs[54] = state; +// attachInterrupt(54, isr54, CHANGE); +// break; +// #endif +// #ifdef CORE_INT55_PIN +// case CORE_INT55_PIN: +// interruptArgs[55] = state; +// attachInterrupt(55, isr55, CHANGE); +// break; +// #endif +// #ifdef CORE_INT56_PIN +// case CORE_INT56_PIN: +// interruptArgs[56] = state; +// attachInterrupt(56, isr56, CHANGE); +// break; +// #endif +// #ifdef CORE_INT57_PIN +// case CORE_INT57_PIN: +// interruptArgs[57] = state; +// attachInterrupt(57, isr57, CHANGE); +// break; +// #endif +// #ifdef CORE_INT58_PIN +// case CORE_INT58_PIN: +// interruptArgs[58] = state; +// attachInterrupt(58, isr58, CHANGE); +// break; +// #endif +// #ifdef CORE_INT59_PIN +// case CORE_INT59_PIN: +// interruptArgs[59] = state; +// attachInterrupt(59, isr59, CHANGE); +// break; +// #endif +// default: +// return 0; +// } +// return 1; +// } +// #endif // ENCODER_USE_INTERRUPTS + + +// #if defined(ENCODER_USE_INTERRUPTS) && !defined(ENCODER_OPTIMIZE_INTERRUPTS) +// #ifdef CORE_INT0_PIN +// static ENCODER_ISR_ATTR void isr0(void) { update(interruptArgs[0]); } +// #endif +// #ifdef CORE_INT1_PIN +// static ENCODER_ISR_ATTR void isr1(void) { update(interruptArgs[1]); } +// #endif +// #ifdef CORE_INT2_PIN +// static ENCODER_ISR_ATTR void isr2(void) { update(interruptArgs[2]); } +// #endif +// #ifdef CORE_INT3_PIN +// static ENCODER_ISR_ATTR void isr3(void) { update(interruptArgs[3]); } +// #endif +// #ifdef CORE_INT4_PIN +// static ENCODER_ISR_ATTR void isr4(void) { update(interruptArgs[4]); } +// #endif +// #ifdef CORE_INT5_PIN +// static ENCODER_ISR_ATTR void isr5(void) { update(interruptArgs[5]); } +// #endif +// #ifdef CORE_INT6_PIN +// static ENCODER_ISR_ATTR void isr6(void) { update(interruptArgs[6]); } +// #endif +// #ifdef CORE_INT7_PIN +// static ENCODER_ISR_ATTR void isr7(void) { update(interruptArgs[7]); } +// #endif +// #ifdef CORE_INT8_PIN +// static ENCODER_ISR_ATTR void isr8(void) { update(interruptArgs[8]); } +// #endif +// #ifdef CORE_INT9_PIN +// static ENCODER_ISR_ATTR void isr9(void) { update(interruptArgs[9]); } +// #endif +// #ifdef CORE_INT10_PIN +// static ENCODER_ISR_ATTR void isr10(void) { update(interruptArgs[10]); } +// #endif +// #ifdef CORE_INT11_PIN +// static ENCODER_ISR_ATTR void isr11(void) { update(interruptArgs[11]); } +// #endif +// #ifdef CORE_INT12_PIN +// static ENCODER_ISR_ATTR void isr12(void) { update(interruptArgs[12]); } +// #endif +// #ifdef CORE_INT13_PIN +// static ENCODER_ISR_ATTR void isr13(void) { update(interruptArgs[13]); } +// #endif +// #ifdef CORE_INT14_PIN +// static ENCODER_ISR_ATTR void isr14(void) { update(interruptArgs[14]); } +// #endif +// #ifdef CORE_INT15_PIN +// static ENCODER_ISR_ATTR void isr15(void) { update(interruptArgs[15]); } +// #endif +// #ifdef CORE_INT16_PIN +// static ENCODER_ISR_ATTR void isr16(void) { update(interruptArgs[16]); } +// #endif +// #ifdef CORE_INT17_PIN +// static ENCODER_ISR_ATTR void isr17(void) { update(interruptArgs[17]); } +// #endif +// #ifdef CORE_INT18_PIN +// static ENCODER_ISR_ATTR void isr18(void) { update(interruptArgs[18]); } +// #endif +// #ifdef CORE_INT19_PIN +// static ENCODER_ISR_ATTR void isr19(void) { update(interruptArgs[19]); } +// #endif +// #ifdef CORE_INT20_PIN +// static ENCODER_ISR_ATTR void isr20(void) { update(interruptArgs[20]); } +// #endif +// #ifdef CORE_INT21_PIN +// static ENCODER_ISR_ATTR void isr21(void) { update(interruptArgs[21]); } +// #endif +// #ifdef CORE_INT22_PIN +// static ENCODER_ISR_ATTR void isr22(void) { update(interruptArgs[22]); } +// #endif +// #ifdef CORE_INT23_PIN +// static ENCODER_ISR_ATTR void isr23(void) { update(interruptArgs[23]); } +// #endif +// #ifdef CORE_INT24_PIN +// static ENCODER_ISR_ATTR void isr24(void) { update(interruptArgs[24]); } +// #endif +// #ifdef CORE_INT25_PIN +// static ENCODER_ISR_ATTR void isr25(void) { update(interruptArgs[25]); } +// #endif +// #ifdef CORE_INT26_PIN +// static ENCODER_ISR_ATTR void isr26(void) { update(interruptArgs[26]); } +// #endif +// #ifdef CORE_INT27_PIN +// static ENCODER_ISR_ATTR void isr27(void) { update(interruptArgs[27]); } +// #endif +// #ifdef CORE_INT28_PIN +// static ENCODER_ISR_ATTR void isr28(void) { update(interruptArgs[28]); } +// #endif +// #ifdef CORE_INT29_PIN +// static ENCODER_ISR_ATTR void isr29(void) { update(interruptArgs[29]); } +// #endif +// #ifdef CORE_INT30_PIN +// static ENCODER_ISR_ATTR void isr30(void) { update(interruptArgs[30]); } +// #endif +// #ifdef CORE_INT31_PIN +// static ENCODER_ISR_ATTR void isr31(void) { update(interruptArgs[31]); } +// #endif +// #ifdef CORE_INT32_PIN +// static ENCODER_ISR_ATTR void isr32(void) { update(interruptArgs[32]); } +// #endif +// #ifdef CORE_INT33_PIN +// static ENCODER_ISR_ATTR void isr33(void) { update(interruptArgs[33]); } +// #endif +// #ifdef CORE_INT34_PIN +// static ENCODER_ISR_ATTR void isr34(void) { update(interruptArgs[34]); } +// #endif +// #ifdef CORE_INT35_PIN +// static ENCODER_ISR_ATTR void isr35(void) { update(interruptArgs[35]); } +// #endif +// #ifdef CORE_INT36_PIN +// static ENCODER_ISR_ATTR void isr36(void) { update(interruptArgs[36]); } +// #endif +// #ifdef CORE_INT37_PIN +// static ENCODER_ISR_ATTR void isr37(void) { update(interruptArgs[37]); } +// #endif +// #ifdef CORE_INT38_PIN +// static ENCODER_ISR_ATTR void isr38(void) { update(interruptArgs[38]); } +// #endif +// #ifdef CORE_INT39_PIN +// static ENCODER_ISR_ATTR void isr39(void) { update(interruptArgs[39]); } +// #endif +// #ifdef CORE_INT40_PIN +// static ENCODER_ISR_ATTR void isr40(void) { update(interruptArgs[40]); } +// #endif +// #ifdef CORE_INT41_PIN +// static ENCODER_ISR_ATTR void isr41(void) { update(interruptArgs[41]); } +// #endif +// #ifdef CORE_INT42_PIN +// static ENCODER_ISR_ATTR void isr42(void) { update(interruptArgs[42]); } +// #endif +// #ifdef CORE_INT43_PIN +// static ENCODER_ISR_ATTR void isr43(void) { update(interruptArgs[43]); } +// #endif +// #ifdef CORE_INT44_PIN +// static ENCODER_ISR_ATTR void isr44(void) { update(interruptArgs[44]); } +// #endif +// #ifdef CORE_INT45_PIN +// static ENCODER_ISR_ATTR void isr45(void) { update(interruptArgs[45]); } +// #endif +// #ifdef CORE_INT46_PIN +// static ENCODER_ISR_ATTR void isr46(void) { update(interruptArgs[46]); } +// #endif +// #ifdef CORE_INT47_PIN +// static ENCODER_ISR_ATTR void isr47(void) { update(interruptArgs[47]); } +// #endif +// #ifdef CORE_INT48_PIN +// static ENCODER_ISR_ATTR void isr48(void) { update(interruptArgs[48]); } +// #endif +// #ifdef CORE_INT49_PIN +// static ENCODER_ISR_ATTR void isr49(void) { update(interruptArgs[49]); } +// #endif +// #ifdef CORE_INT50_PIN +// static ENCODER_ISR_ATTR void isr50(void) { update(interruptArgs[50]); } +// #endif +// #ifdef CORE_INT51_PIN +// static ENCODER_ISR_ATTR void isr51(void) { update(interruptArgs[51]); } +// #endif +// #ifdef CORE_INT52_PIN +// static ENCODER_ISR_ATTR void isr52(void) { update(interruptArgs[52]); } +// #endif +// #ifdef CORE_INT53_PIN +// static ENCODER_ISR_ATTR void isr53(void) { update(interruptArgs[53]); } +// #endif +// #ifdef CORE_INT54_PIN +// static ENCODER_ISR_ATTR void isr54(void) { update(interruptArgs[54]); } +// #endif +// #ifdef CORE_INT55_PIN +// static ENCODER_ISR_ATTR void isr55(void) { update(interruptArgs[55]); } +// #endif +// #ifdef CORE_INT56_PIN +// static ENCODER_ISR_ATTR void isr56(void) { update(interruptArgs[56]); } +// #endif +// #ifdef CORE_INT57_PIN +// static ENCODER_ISR_ATTR void isr57(void) { update(interruptArgs[57]); } +// #endif +// #ifdef CORE_INT58_PIN +// static ENCODER_ISR_ATTR void isr58(void) { update(interruptArgs[58]); } +// #endif +// #ifdef CORE_INT59_PIN +// static ENCODER_ISR_ATTR void isr59(void) { update(interruptArgs[59]); } +// #endif +// #endif +// }; + +// #if defined(ENCODER_USE_INTERRUPTS) && defined(ENCODER_OPTIMIZE_INTERRUPTS) +// #if defined(__AVR__) +// #if defined(INT0_vect) && CORE_NUM_INTERRUPT > 0 +// ISR(INT0_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(0)]); } +// #endif +// #if defined(INT1_vect) && CORE_NUM_INTERRUPT > 1 +// ISR(INT1_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(1)]); } +// #endif +// #if defined(INT2_vect) && CORE_NUM_INTERRUPT > 2 +// ISR(INT2_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(2)]); } +// #endif +// #if defined(INT3_vect) && CORE_NUM_INTERRUPT > 3 +// ISR(INT3_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(3)]); } +// #endif +// #if defined(INT4_vect) && CORE_NUM_INTERRUPT > 4 +// ISR(INT4_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(4)]); } +// #endif +// #if defined(INT5_vect) && CORE_NUM_INTERRUPT > 5 +// ISR(INT5_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(5)]); } +// #endif +// #if defined(INT6_vect) && CORE_NUM_INTERRUPT > 6 +// ISR(INT6_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(6)]); } +// #endif +// #if defined(INT7_vect) && CORE_NUM_INTERRUPT > 7 +// ISR(INT7_vect) { Encoder::update(Encoder::interruptArgs[SCRAMBLE_INT_ORDER(7)]); } +// #endif +// #endif // AVR +// #if defined(attachInterrupt) +// // Don't intefere with other libraries or sketch use of attachInterrupt() +// // https://github.com/PaulStoffregen/Encoder/issues/8 +// #undef attachInterrupt +// #endif +// #endif // ENCODER_OPTIMIZE_INTERRUPTS + + +// #endif \ No newline at end of file diff --git a/firmware/lib/encoder/examples/Basic/Basic.pde b/firmware/lib/encoder/examples/Basic/Basic.pde new file mode 100644 index 0000000..3394b58 --- /dev/null +++ b/firmware/lib/encoder/examples/Basic/Basic.pde @@ -0,0 +1,29 @@ +/* Encoder Library - Basic Example + * http://www.pjrc.com/teensy/td_libs_Encoder.html + * + * This example code is in the public domain. + */ + +#include + +// Change these two numbers to the pins connected to your encoder. +// Best Performance: both pins have interrupt capability +// Good Performance: only the first pin has interrupt capability +// Low Performance: neither pin has interrupt capability +Encoder myEnc(5, 6); +// avoid using pins with LEDs attached + +void setup() { + Serial.begin(9600); + Serial.println("Basic Encoder Test:"); +} + +long oldPosition = -999; + +void loop() { + long newPosition = myEnc.read(); + if (newPosition != oldPosition) { + oldPosition = newPosition; + Serial.println(newPosition); + } +} diff --git a/firmware/lib/encoder/examples/NoInterrupts/NoInterrupts.pde b/firmware/lib/encoder/examples/NoInterrupts/NoInterrupts.pde new file mode 100644 index 0000000..b890652 --- /dev/null +++ b/firmware/lib/encoder/examples/NoInterrupts/NoInterrupts.pde @@ -0,0 +1,46 @@ +/* Encoder Library - NoInterrupts Example + * http://www.pjrc.com/teensy/td_libs_Encoder.html + * + * This example code is in the public domain. + */ + +// If you define ENCODER_DO_NOT_USE_INTERRUPTS *before* including +// Encoder, the library will never use interrupts. This is mainly +// useful to reduce the size of the library when you are using it +// with pins that do not support interrupts. Without interrupts, +// your program must call the read() function rapidly, or risk +// missing changes in position. +#define ENCODER_DO_NOT_USE_INTERRUPTS +#include + +// Beware of Serial.print() speed. Without interrupts, if you +// transmit too much data with Serial.print() it can slow your +// reading from Encoder. Arduino 1.0 has improved transmit code. +// Using the fastest baud rate also helps. Teensy has USB packet +// buffering. But all boards can experience problems if you print +// too much and fill up buffers. + +// Change these two numbers to the pins connected to your encoder. +// With ENCODER_DO_NOT_USE_INTERRUPTS, no interrupts are ever +// used, even if the pin has interrupt capability +Encoder myEnc(5, 6); +// avoid using pins with LEDs attached + +void setup() { + Serial.begin(9600); + Serial.println("Basic NoInterrupts Test:"); +} + +long position = -999; + +void loop() { + long newPos = myEnc.read(); + if (newPos != position) { + position = newPos; + Serial.println(position); + } + // With any substantial delay added, Encoder can only track + // very slow motion. You may uncomment this line to see + // how badly a delay affects your encoder. + //delay(50); +} diff --git a/firmware/lib/encoder/examples/SpeedTest/SpeedTest.pde b/firmware/lib/encoder/examples/SpeedTest/SpeedTest.pde new file mode 100644 index 0000000..76cf350 --- /dev/null +++ b/firmware/lib/encoder/examples/SpeedTest/SpeedTest.pde @@ -0,0 +1,113 @@ +/* Encoder Library - SpeedTest - for measuring maximum Encoder speed + * http://www.pjrc.com/teensy/td_libs_Encoder.html + * + * This example code is in the public domain. + */ + + +// This SpeedTest example provides a simple way to verify how much +// CPU time Encoder is consuming. Connect a DC voltmeter to the +// output pin and measure the voltage while the encoder is stopped +// or running at a very slow speed. Even though the pin is rapidly +// pulsing, a DC voltmeter will show the average voltage. Due to +// software timing, it will read a number much less than a steady +// logic high, but this number will give you a baseline reading +// for output with minimal interrupt overhead. Then increase the +// encoder speed. The voltage will decrease as the processor spends +// more time in Encoder's interrupt routines counting the pulses +// and less time pulsing the output pin. When the voltage is +// close to zero and will not decrease any farther, you have reached +// the absolute speed limit. Or, if using a mechanical system where +// you reach a speed limit imposed by your motors or other hardware, +// the amount this voltage has decreased, compared to the baseline, +// should give you a good approximation of the portion of available +// CPU time Encoder is consuming at your maximum speed. + +// Encoder requires low latency interrupt response. Available CPU +// time does NOT necessarily prove or guarantee correct performance. +// If another library, like NewSoftSerial, is disabling interrupts +// for lengthy periods of time, Encoder can be prevented from +// properly counting the intput signals while interrupt are disabled. + + +// This optional setting causes Encoder to use more optimized code, +// but the downside is a conflict if any other part of your sketch +// or any other library you're using requires attachInterrupt(). +// It must be defined before Encoder.h is included. +//#define ENCODER_OPTIMIZE_INTERRUPTS + +#include +#include "pins_arduino.h" + +// Change these two numbers to the pins connected to your encoder +// or shift register circuit which emulates a quadrature encoder +// case 1: both pins are interrupts +// case 2: only first pin used as interrupt +Encoder myEnc(5, 6); + +// Connect a DC voltmeter to this pin. +const int outputPin = 12; + +/* This simple circuit, using a Dual Flip-Flop chip, can emulate + quadrature encoder signals. The clock can come from a fancy + function generator or a cheap 555 timer chip. The clock + frequency can be measured with another board running FreqCount + http://www.pjrc.com/teensy/td_libs_FreqCount.html + + +5V + | Quadrature Encoder Signal Emulator + Clock | + Input o----*-------------------------- ---------------------------o Output1 + | |14 | | + | _______|_______ | | _______________ + | | CD4013 | | | | CD4013 | + | 5 | | 1 | | 9 | | 13 + ---------| D Q |-----|----*----| D Q |------o Output2 + | | | | | | | + | | 3 | | | 11 | | + | ----|> Clk | ---------|> Clk | + | | | | | + | 6 | | 8 | | + | ----| S | ----| S | + | | | | | | | + | | 4 | _ | 2 | 10 | _ | 12 + | *----| R Q |--- *----| R Q |---- + | | | | | | | | + | | |_______________| | |_______________| | + | | | | | + | | | 7 | | + | | | | | + -------------------------------------------------------------- + | | | + | | | + ----- ----- ----- + --- --- --- + - - - +*/ + + +void setup() { + pinMode(outputPin, OUTPUT); +} + +#if defined(__AVR__) +#define REGTYPE unsigned char +#elif defined(__PIC32MX__) +#define REGTYPE unsigned long +#endif + +void loop() { + volatile int count = 0; + volatile REGTYPE *reg = portOutputRegister(digitalPinToPort(outputPin)); + REGTYPE mask = digitalPinToBitMask(outputPin); + + while (1) { + myEnc.read(); // Read the encoder while interrupts are enabled. + noInterrupts(); + *reg |= mask; // Pulse the pin high, while interrupts are disabled. + count = count + 1; + *reg &= ~mask; + interrupts(); + } +} + diff --git a/firmware/lib/encoder/examples/TwoKnobs/TwoKnobs.pde b/firmware/lib/encoder/examples/TwoKnobs/TwoKnobs.pde new file mode 100644 index 0000000..306b33e --- /dev/null +++ b/firmware/lib/encoder/examples/TwoKnobs/TwoKnobs.pde @@ -0,0 +1,46 @@ +/* Encoder Library - TwoKnobs Example + * http://www.pjrc.com/teensy/td_libs_Encoder.html + * + * This example code is in the public domain. + */ + +#include + +// Change these pin numbers to the pins connected to your encoder. +// Best Performance: both pins have interrupt capability +// Good Performance: only the first pin has interrupt capability +// Low Performance: neither pin has interrupt capability +Encoder knobLeft(5, 6); +Encoder knobRight(7, 8); +// avoid using pins with LEDs attached + +void setup() { + Serial.begin(9600); + Serial.println("TwoKnobs Encoder Test:"); +} + +long positionLeft = -999; +long positionRight = -999; + +void loop() { + long newLeft, newRight; + newLeft = knobLeft.read(); + newRight = knobRight.read(); + if (newLeft != positionLeft || newRight != positionRight) { + Serial.print("Left = "); + Serial.print(newLeft); + Serial.print(", Right = "); + Serial.print(newRight); + Serial.println(); + positionLeft = newLeft; + positionRight = newRight; + } + // if a character is sent from the serial monitor, + // reset both back to zero. + if (Serial.available()) { + Serial.read(); + Serial.println("Reset both knobs to zero"); + knobLeft.write(0); + knobRight.write(0); + } +} diff --git a/firmware/lib/encoder/keywords.txt b/firmware/lib/encoder/keywords.txt new file mode 100644 index 0000000..a4baa01 --- /dev/null +++ b/firmware/lib/encoder/keywords.txt @@ -0,0 +1,4 @@ +ENCODER_USE_INTERRUPTS LITERAL1 +ENCODER_OPTIMIZE_INTERRUPTS LITERAL1 +ENCODER_DO_NOT_USE_INTERRUPTS LITERAL1 +Encoder KEYWORD1 diff --git a/firmware/lib/encoder/utility/direct_pin_read.h b/firmware/lib/encoder/utility/direct_pin_read.h new file mode 100644 index 0000000..3341d13 --- /dev/null +++ b/firmware/lib/encoder/utility/direct_pin_read.h @@ -0,0 +1,110 @@ +#ifndef direct_pin_read_h_ +#define direct_pin_read_h_ + +#if defined(__AVR__) + +#define IO_REG_TYPE uint8_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(TEENSYDUINO) && (defined(KINETISK) || defined(KINETISL)) + +#define IO_REG_TYPE uint8_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__IMXRT1052__) || defined(__IMXRT1062__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portOutputRegister(pin)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__SAM3X8E__) // || defined(ESP8266) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__PIC32MX__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portModeRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base+4)) & (mask)) ? 1 : 0) + +/* ESP8266 v2.0.0 Arduino workaround for bug https://github.com/esp8266/Arduino/issues/1110 */ +#elif defined(ESP8266) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) ((volatile uint32_t *)(0x60000000+(0x318))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +/* ESP32 Arduino (https://github.com/espressif/arduino-esp32) */ +#elif defined(ESP32) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (portInputRegister(digitalPinToPort(pin))) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(__SAMD21G18A__) || defined(__SAMD21E18A__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) portModeRegister(digitalPinToPort(pin)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*((base)+8)) & (mask)) ? 1 : 0) + +#elif defined(__SAMD51__) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) portInputRegister(digitalPinToPort(pin)) +#define PIN_TO_BITMASK(pin) (digitalPinToBitMask(pin)) +#define DIRECT_PIN_READ(base, mask) (((*(base)) & (mask)) ? 1 : 0) + +#elif defined(RBL_NRF51822) + +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (0) +#define PIN_TO_BITMASK(pin) (pin) +#define DIRECT_PIN_READ(base, pin) nrf_gpio_pin_read(pin) + +#elif defined(ARDUINO_ARCH_NRF52840) +#define IO_REG_TYPE uint32_t +#define PIN_TO_BASEREG(pin) (0) +#define PIN_TO_BITMASK(pin) digitalPinToPinName(pin) +#define DIRECT_PIN_READ(base, pin) nrf_gpio_pin_read(pin) + +#elif defined(__arc__) /* Arduino101/Genuino101 specifics */ + +#include "scss_registers.h" +#include "portable.h" +#include "avr/pgmspace.h" +#define GPIO_ID(pin) (g_APinDescription[pin].ulGPIOId) +#define GPIO_TYPE(pin) (g_APinDescription[pin].ulGPIOType) +#define GPIO_BASE(pin) (g_APinDescription[pin].ulGPIOBase) +#define EXT_PORT_OFFSET_SS 0x0A +#define EXT_PORT_OFFSET_SOC 0x50 +#define PIN_TO_BASEREG(pin) ((volatile uint32_t *)g_APinDescription[pin].ulGPIOBase) +#define PIN_TO_BITMASK(pin) pin +#define IO_REG_TYPE uint32_t +static inline __attribute__((always_inline)) +IO_REG_TYPE directRead(volatile IO_REG_TYPE *base, IO_REG_TYPE pin) +{ + IO_REG_TYPE ret; + if (SS_GPIO == GPIO_TYPE(pin)) { + ret = READ_ARC_REG(((IO_REG_TYPE)base + EXT_PORT_OFFSET_SS)); + } else { + ret = MMIO_REG_VAL_FROM_BASE((IO_REG_TYPE)base, EXT_PORT_OFFSET_SOC); + } + return ((ret >> GPIO_ID(pin)) & 0x01); +} +#define DIRECT_PIN_READ(base, pin) directRead(base, pin) + +#endif + +#endif \ No newline at end of file diff --git a/firmware/lib/encoder/utility/interrupt_config.h b/firmware/lib/encoder/utility/interrupt_config.h new file mode 100644 index 0000000..cde6adf --- /dev/null +++ b/firmware/lib/encoder/utility/interrupt_config.h @@ -0,0 +1,87 @@ +#if defined(__AVR__) + +#include +#include + +#define attachInterrupt(num, func, mode) enableInterrupt(num) +#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +#define SCRAMBLE_INT_ORDER(num) ((num < 4) ? num + 2 : ((num < 6) ? num - 4 : num)) +#define DESCRAMBLE_INT_ORDER(num) ((num < 2) ? num + 4 : ((num < 6) ? num - 2 : num)) +#else +#define SCRAMBLE_INT_ORDER(num) (num) +#define DESCRAMBLE_INT_ORDER(num) (num) +#endif + +static void enableInterrupt(uint8_t num) +{ + switch (DESCRAMBLE_INT_ORDER(num)) { + #if defined(EICRA) && defined(EIMSK) + case 0: + EICRA = (EICRA & 0xFC) | 0x01; + EIMSK |= 0x01; + return; + case 1: + EICRA = (EICRA & 0xF3) | 0x04; + EIMSK |= 0x02; + return; + case 2: + EICRA = (EICRA & 0xCF) | 0x10; + EIMSK |= 0x04; + return; + case 3: + EICRA = (EICRA & 0x3F) | 0x40; + EIMSK |= 0x08; + return; + #elif defined(MCUCR) && defined(GICR) + case 0: + MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); + GICR |= (1 << INT0); + return; + case 1: + MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); + GICR |= (1 << INT1); + return; + #elif defined(MCUCR) && defined(GIMSK) + case 0: + MCUCR = (MCUCR & ~((1 << ISC00) | (1 << ISC01))) | (mode << ISC00); + GIMSK |= (1 << INT0); + return; + case 1: + MCUCR = (MCUCR & ~((1 << ISC10) | (1 << ISC11))) | (mode << ISC10); + GIMSK |= (1 << INT1); + return; + #endif + #if defined(EICRB) && defined(EIMSK) + case 4: + EICRB = (EICRB & 0xFC) | 0x01; + EIMSK |= 0x10; + return; + case 5: + EICRB = (EICRB & 0xF3) | 0x04; + EIMSK |= 0x20; + return; + case 6: + EICRB = (EICRB & 0xCF) | 0x10; + EIMSK |= 0x40; + return; + case 7: + EICRB = (EICRB & 0x3F) | 0x40; + EIMSK |= 0x80; + return; + #endif + } +} + +#elif defined(__PIC32MX__) + +#ifdef ENCODER_OPTIMIZE_INTERRUPTS +#undef ENCODER_OPTIMIZE_INTERRUPTS +#endif + +#else + +#ifdef ENCODER_OPTIMIZE_INTERRUPTS +#undef ENCODER_OPTIMIZE_INTERRUPTS +#endif + +#endif diff --git a/firmware/lib/encoder/utility/interrupt_pins.h b/firmware/lib/encoder/utility/interrupt_pins.h new file mode 100644 index 0000000..ed4ea18 --- /dev/null +++ b/firmware/lib/encoder/utility/interrupt_pins.h @@ -0,0 +1,369 @@ +// interrupt pins for known boards + +// Teensy (and maybe others) define these automatically +#if !defined(CORE_NUM_INTERRUPT) + +// Wiring boards +#if defined(WIRING) + #define CORE_NUM_INTERRUPT NUM_EXTERNAL_INTERRUPTS + #if NUM_EXTERNAL_INTERRUPTS > 0 + #define CORE_INT0_PIN EI0 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 1 + #define CORE_INT1_PIN EI1 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 2 + #define CORE_INT2_PIN EI2 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 3 + #define CORE_INT3_PIN EI3 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 4 + #define CORE_INT4_PIN EI4 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 5 + #define CORE_INT5_PIN EI5 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 6 + #define CORE_INT6_PIN EI6 + #endif + #if NUM_EXTERNAL_INTERRUPTS > 7 + #define CORE_INT7_PIN EI7 + #endif + +// Arduino Uno, Duemilanove, Diecimila, LilyPad, Mini, Fio, etc... +#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328PB__) ||defined(__AVR_ATmega168__) || defined(__AVR_ATmega8__) + #define CORE_NUM_INTERRUPT 2 + #define CORE_INT0_PIN 2 + #define CORE_INT1_PIN 3 + +// Arduino Mega +#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #define CORE_NUM_INTERRUPT 6 + #define CORE_INT0_PIN 2 + #define CORE_INT1_PIN 3 + #define CORE_INT2_PIN 21 + #define CORE_INT3_PIN 20 + #define CORE_INT4_PIN 19 + #define CORE_INT5_PIN 18 + +// Arduino Nano Every, Uno R2 Wifi +#elif defined(__AVR_ATmega4809__) + #define CORE_NUM_INTERRUPT 22 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT20_PIN 20 + #define CORE_INT21_PIN 21 + +// Arduino Leonardo (untested) +#elif defined(__AVR_ATmega32U4__) && !defined(CORE_TEENSY) + #define CORE_NUM_INTERRUPT 5 + #define CORE_INT0_PIN 3 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 0 + #define CORE_INT3_PIN 1 + #define CORE_INT4_PIN 7 + +// Sanguino (untested) and ATmega1284P +#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega1284P__) + #define CORE_NUM_INTERRUPT 3 + #define CORE_INT0_PIN 10 + #define CORE_INT1_PIN 11 + #define CORE_INT2_PIN 2 + +// ATmega32u2 and ATmega32u16 based boards with HoodLoader2 +#elif defined(__AVR_ATmega32U2__) || defined(__AVR_ATmega16U2__) + #define CORE_NUM_INTERRUPT 8 + #define CORE_INT0_PIN 8 + #define CORE_INT1_PIN 17 + #define CORE_INT2_PIN 13 + #define CORE_INT3_PIN 14 + #define CORE_INT4_PIN 15 + #define CORE_INT5_PIN 16 + #define CORE_INT6_PIN 19 + #define CORE_INT7_PIN 20 + +// Chipkit Uno32 - attachInterrupt may not support CHANGE option +#elif defined(__PIC32MX__) && defined(_BOARD_UNO_) + #define CORE_NUM_INTERRUPT 5 + #define CORE_INT0_PIN 38 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 7 + #define CORE_INT3_PIN 8 + #define CORE_INT4_PIN 35 + +// Chipkit Uno32 - attachInterrupt may not support CHANGE option +#elif defined(__PIC32MX__) && defined(_BOARD_MEGA_) + #define CORE_NUM_INTERRUPT 5 + #define CORE_INT0_PIN 3 + #define CORE_INT1_PIN 2 + #define CORE_INT2_PIN 7 + #define CORE_INT3_PIN 21 + #define CORE_INT4_PIN 20 + +// http://hlt.media.mit.edu/?p=1229 +#elif defined(__AVR_ATtiny45__) || defined(__AVR_ATtiny85__) + #define CORE_NUM_INTERRUPT 1 + #define CORE_INT0_PIN 2 + + // ATtiny44 ATtiny84 +#elif defined(__AVR_ATtiny44__) || defined(__AVR_ATtiny84__) + #define CORE_NUM_INTERRUPT 1 + #define CORE_INT0_PIN 8 + +// ATtiny441 ATtiny841 +#elif defined(__AVR_ATtiny441__) || defined(__AVR_ATtiny841__) + #define CORE_NUM_INTERRUPT 1 + #define CORE_INT0_PIN 9 + +//https://github.com/SpenceKonde/ATTinyCore/blob/master/avr/extras/ATtiny_x313.md +#elif defined(__AVR_ATtinyX313__) + #define CORE_NUM_INTERRUPT 2 + #define CORE_INT0_PIN 4 + #define CORE_INT1_PIN 5 + +// Attiny167 same core as abobe +#elif defined(__AVR_ATtiny167__) + #define CORE_NUM_INTERRUPT 2 + #define CORE_INT0_PIN 14 + #define CORE_INT1_PIN 3 + + +// Arduino Due +#elif defined(__SAM3X8E__) + #define CORE_NUM_INTERRUPT 54 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT20_PIN 20 + #define CORE_INT21_PIN 21 + #define CORE_INT22_PIN 22 + #define CORE_INT23_PIN 23 + #define CORE_INT24_PIN 24 + #define CORE_INT25_PIN 25 + #define CORE_INT26_PIN 26 + #define CORE_INT27_PIN 27 + #define CORE_INT28_PIN 28 + #define CORE_INT29_PIN 29 + #define CORE_INT30_PIN 30 + #define CORE_INT31_PIN 31 + #define CORE_INT32_PIN 32 + #define CORE_INT33_PIN 33 + #define CORE_INT34_PIN 34 + #define CORE_INT35_PIN 35 + #define CORE_INT36_PIN 36 + #define CORE_INT37_PIN 37 + #define CORE_INT38_PIN 38 + #define CORE_INT39_PIN 39 + #define CORE_INT40_PIN 40 + #define CORE_INT41_PIN 41 + #define CORE_INT42_PIN 42 + #define CORE_INT43_PIN 43 + #define CORE_INT44_PIN 44 + #define CORE_INT45_PIN 45 + #define CORE_INT46_PIN 46 + #define CORE_INT47_PIN 47 + #define CORE_INT48_PIN 48 + #define CORE_INT49_PIN 49 + #define CORE_INT50_PIN 50 + #define CORE_INT51_PIN 51 + #define CORE_INT52_PIN 52 + #define CORE_INT53_PIN 53 + +// ESP8266 (https://github.com/esp8266/Arduino/) +#elif defined(ESP8266) + #define CORE_NUM_INTERRUPT EXTERNAL_NUM_INTERRUPTS + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + // GPIO6-GPIO11 are typically used to interface with the flash memory IC on + // most esp8266 modules, so we should avoid adding interrupts to these pins. + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + +// ESP32 (https://github.com/espressif/arduino-esp32) +#elif defined(ESP32) + + #define CORE_NUM_INTERRUPT 40 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + // GPIO6-GPIO11 are typically used to interface with the flash memory IC on + // esp32, so we should avoid adding interrupts to these pins. + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT21_PIN 21 + #define CORE_INT22_PIN 22 + #define CORE_INT23_PIN 23 + #define CORE_INT25_PIN 25 + #define CORE_INT26_PIN 26 + #define CORE_INT27_PIN 27 + #define CORE_INT32_PIN 32 + #define CORE_INT33_PIN 33 + #define CORE_INT34_PIN 34 + #define CORE_INT35_PIN 35 + #define CORE_INT36_PIN 36 + #define CORE_INT39_PIN 39 + + +// Arduino Zero - TODO: interrupts do not seem to work +// please help, contribute a fix! +#elif defined(__SAMD21G18A__) || defined(__SAMD21E18A__) + #define CORE_NUM_INTERRUPT 31 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT20_PIN 20 + #define CORE_INT21_PIN 21 + #define CORE_INT22_PIN 22 + #define CORE_INT23_PIN 23 + #define CORE_INT24_PIN 24 + #define CORE_INT25_PIN 25 + #define CORE_INT26_PIN 26 + #define CORE_INT27_PIN 27 + #define CORE_INT28_PIN 28 + #define CORE_INT29_PIN 29 + #define CORE_INT30_PIN 30 + +#elif defined(__SAMD51__) + #define CORE_NUM_INTERRUPT 26 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN 14 + #define CORE_INT15_PIN 15 + #define CORE_INT16_PIN 16 + #define CORE_INT17_PIN 17 + #define CORE_INT18_PIN 18 + #define CORE_INT19_PIN 19 + #define CORE_INT20_PIN 20 + #define CORE_INT21_PIN 21 + #define CORE_INT22_PIN 22 + #define CORE_INT23_PIN 23 + #define CORE_INT24_PIN 24 + #define CORE_INT25_PIN 25 + +// Arduino 101 +#elif defined(__arc__) + #define CORE_NUM_INTERRUPT 14 + #define CORE_INT2_PIN 2 + #define CORE_INT5_PIN 5 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + +// Arduino Nano 33 BLE +#elif defined(ARDUINO_ARCH_NRF52840) + #define CORE_NUM_INTERRUPT 22 + #define CORE_INT0_PIN 0 + #define CORE_INT1_PIN 1 + #define CORE_INT2_PIN 2 + #define CORE_INT3_PIN 3 + #define CORE_INT4_PIN 4 + #define CORE_INT5_PIN 5 + #define CORE_INT6_PIN 6 + #define CORE_INT7_PIN 7 + #define CORE_INT8_PIN 8 + #define CORE_INT9_PIN 9 + #define CORE_INT10_PIN 10 + #define CORE_INT11_PIN 11 + #define CORE_INT12_PIN 12 + #define CORE_INT13_PIN 13 + #define CORE_INT14_PIN A0 + #define CORE_INT15_PIN A1 + #define CORE_INT16_PIN A2 + #define CORE_INT17_PIN A3 + #define CORE_INT18_PIN A4 + #define CORE_INT19_PIN A5 + #define CORE_INT20_PIN A6 + #define CORE_INT21_PIN A7 +#endif +#endif + +#if !defined(CORE_NUM_INTERRUPT) +#error "Interrupts are unknown for this board, please add to this code" +#endif +#if CORE_NUM_INTERRUPT <= 0 +#error "Encoder requires interrupt pins, but this board does not have any :(" +#error "You could try defining ENCODER_DO_NOT_USE_INTERRUPTS as a kludge." +#endif \ No newline at end of file diff --git a/firmware/lib/imu/ADXL345.cpp b/firmware/lib/imu/ADXL345.cpp new file mode 100644 index 0000000..7890d4c --- /dev/null +++ b/firmware/lib/imu/ADXL345.cpp @@ -0,0 +1,1668 @@ +// I2Cdev library collection - ADXL345 I2C device class +// Based on Analog Devices ADXL345 datasheet rev. C, 5/2011 +// 7/31/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "ADXL345.h" + +/** Default constructor, uses default I2C address. + * @see ADXL345_DEFAULT_ADDRESS + */ +ADXL345::ADXL345() { + devAddr = ADXL345_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see ADXL345_DEFAULT_ADDRESS + * @see ADXL345_ADDRESS_ALT_LOW + * @see ADXL345_ADDRESS_ALT_HIGH + */ +ADXL345::ADXL345(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the accelerometer, so be sure to adjust the power settings + * after you call this method if you want it to enter standby mode, or another + * less demanding mode of operation. + */ +void ADXL345::initialize() { + I2Cdev::writeByte(devAddr, ADXL345_RA_POWER_CTL, 0); // reset all power settings + setAutoSleepEnabled(true); + setMeasureEnabled(true); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool ADXL345::testConnection() { + return getDeviceID() == 0xE5; +} + +// DEVID register + +/** Get Device ID. + * The DEVID register holds a fixed device ID code of 0xE5 (345 octal). + * @return Device ID (should be 0xE5, 229 dec, 345 oct) + * @see ADXL345_RA_DEVID + */ +uint8_t ADXL345::getDeviceID() { + I2Cdev::readByte(devAddr, ADXL345_RA_DEVID, buffer); + return buffer[0]; +} + +// THRESH_TAP register + +/** Get tap threshold. + * The THRESH_TAP register is eight bits and holds the threshold value for tap + * interrupts. The data format is unsigned, therefore, the magnitude of the tap + * event is compared with the value in THRESH_TAP for normal tap detection. The + * scale factor is 62.5 mg/LSB (that is, 0xFF = 16 g). A value of 0 may result + * in undesirable behavior if single tap/double tap interrupts are enabled. + * @return Tap threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_TAP + */ +uint8_t ADXL345::getTapThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_TAP, buffer); + return buffer[0]; +} +/** Set tap threshold. + * @param threshold Tap magnitude threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_TAP + * @see getTapThreshold() + */ +void ADXL345::setTapThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_TAP, threshold); +} + +// OFS* registers + +/** Get axis offsets. + * The OFSX, OFSY, and OFSZ registers are each eight bits and offer user-set + * offset adjustments in twos complement format with a scale factor of 15.6 + * mg/LSB (that is, 0x7F = 2 g). The value stored in the offset registers is + * automatically added to the acceleration data, and the resulting value is + * stored in the output data registers. For additional information regarding + * offset calibration and the use of the offset registers, refer to the Offset + * Calibration section of the datasheet. + * @param x X axis offset container + * @param y Y axis offset container + * @param z Z axis offset container + * @see ADXL345_RA_OFSX + * @see ADXL345_RA_OFSY + * @see ADXL345_RA_OFSZ + */ +void ADXL345::getOffset(int8_t* x, int8_t* y, int8_t* z) { + I2Cdev::readBytes(devAddr, ADXL345_RA_OFSX, 3, buffer); + *x = buffer[0]; + *y = buffer[1]; + *z = buffer[2]; +} +/** Set axis offsets. + * @param x X axis offset value + * @param y Y axis offset value + * @param z Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + * @see ADXL345_RA_OFSY + * @see ADXL345_RA_OFSZ + */ +void ADXL345::setOffset(int8_t x, int8_t y, int8_t z) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSX, x); + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSY, y); + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSZ, z); +} +/** Get X axis offset. + * @return X axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + */ +int8_t ADXL345::getOffsetX() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSX, buffer); + return buffer[0]; +} +/** Set X axis offset. + * @param x X axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + */ +void ADXL345::setOffsetX(int8_t x) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSX, x); +} +/** Get Y axis offset. + * @return Y axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSY + */ +int8_t ADXL345::getOffsetY() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSY, buffer); + return buffer[0]; +} +/** Set Y axis offset. + * @param y Y axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSY + */ +void ADXL345::setOffsetY(int8_t y) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSY, y); +} +/** Get Z axis offset. + * @return Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSZ + */ +int8_t ADXL345::getOffsetZ() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSZ, buffer); + return buffer[0]; +} +/** Set Z axis offset. + * @param z Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSZ + */ +void ADXL345::setOffsetZ(int8_t z) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSZ, z); +} + +// DUR register + +/** Get tap duration. + * The DUR register is eight bits and contains an unsigned time value + * representing the maximum time that an event must be above the THRESH_TAP + * threshold to qualify as a tap event. The scale factor is 625 us/LSB. A value + * of 0 disables the single tap/ double tap functions. + * @return Tap duration (scaled at 625 us/LSB) + * @see ADXL345_RA_DUR + */ +uint8_t ADXL345::getTapDuration() { + I2Cdev::readByte(devAddr, ADXL345_RA_DUR, buffer); + return buffer[0]; +} +/** Set tap duration. + * @param duration Tap duration (scaled at 625 us/LSB) + * @see getTapDuration() + * @see ADXL345_RA_DUR + */ +void ADXL345::setTapDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, ADXL345_RA_DUR, duration); +} + +// LATENT register + +/** Get tap duration. + * The latent register is eight bits and contains an unsigned time value + * representing the wait time from the detection of a tap event to the start of + * the time window (defined by the window register) during which a possible + * second tap event can be detected. The scale factor is 1.25 ms/LSB. A value of + * 0 disables the double tap function. + * @return Tap latency (scaled at 1.25 ms/LSB) + * @see ADXL345_RA_LATENT + */ +uint8_t ADXL345::getDoubleTapLatency() { + I2Cdev::readByte(devAddr, ADXL345_RA_LATENT, buffer); + return buffer[0]; +} +/** Set tap duration. + * @param latency Tap latency (scaled at 1.25 ms/LSB) + * @see getDoubleTapLatency() + * @see ADXL345_RA_LATENT + */ +void ADXL345::setDoubleTapLatency(uint8_t latency) { + I2Cdev::writeByte(devAddr, ADXL345_RA_LATENT, latency); +} + +// WINDOW register + +/** Get double tap window. + * The window register is eight bits and contains an unsigned time value + * representing the amount of time after the expiration of the latency time + * (determined by the latent register) during which a second valid tap can + * begin. The scale factor is 1.25 ms/LSB. A value of 0 disables the double tap + * function. + * @return Double tap window (scaled at 1.25 ms/LSB) + * @see ADXL345_RA_WINDOW + */ +uint8_t ADXL345::getDoubleTapWindow() { + I2Cdev::readByte(devAddr, ADXL345_RA_WINDOW, buffer); + return buffer[0]; +} +/** Set double tap window. + * @param window Double tap window (scaled at 1.25 ms/LSB) + * @see getDoubleTapWindow() + * @see ADXL345_RA_WINDOW + */ +void ADXL345::setDoubleTapWindow(uint8_t window) { + I2Cdev::writeByte(devAddr, ADXL345_RA_WINDOW, window); +} + +// THRESH_ACT register + +/** Get activity threshold. + * The THRESH_ACT register is eight bits and holds the threshold value for + * detecting activity. The data format is unsigned, so the magnitude of the + * activity event is compared with the value in the THRESH_ACT register. The + * scale factor is 62.5 mg/LSB. A value of 0 may result in undesirable behavior + * if the activity interrupt is enabled. + * @return Activity threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_ACT + */ +uint8_t ADXL345::getActivityThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_ACT, buffer); + return buffer[0]; +} +/** Set activity threshold. + * @param threshold Activity threshold (scaled at 62.5 mg/LSB) + * @see getActivityThreshold() + * @see ADXL345_RA_THRESH_ACT + */ +void ADXL345::setActivityThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_ACT, threshold); +} + +// THRESH_INACT register + +/** Get inactivity threshold. + * The THRESH_INACT register is eight bits and holds the threshold value for + * detecting inactivity. The data format is unsigned, so the magnitude of the + * inactivity event is compared with the value in the THRESH_INACT register. The + * scale factor is 62.5 mg/LSB. A value of 0 may result in undesirable behavior + * if the inactivity interrupt is enabled. + * @return Inactivity threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_INACT + */ +uint8_t ADXL345::getInactivityThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_INACT, buffer); + return buffer[0]; +} +/** Set inactivity threshold. + * @param threshold Inctivity threshold (scaled at 62.5 mg/LSB) + * @see getInctivityThreshold() + * @see ADXL345_RA_THRESH_INACT + */ +void ADXL345::setInactivityThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_INACT, threshold); +} + +// TIME_INACT register + +/** Set inactivity time. + * The TIME_INACT register is eight bits and contains an unsigned time value + * representing the amount of time that acceleration must be less than the value + * in the THRESH_INACT register for inactivity to be declared. The scale factor + * is 1 sec/LSB. Unlike the other interrupt functions, which use unfiltered data + * (see the Threshold sectionof the datasheet), the inactivity function uses + * filtered output data. At least one output sample must be generated for the + * inactivity interrupt to be triggered. This results in the function appearing + * unresponsive if the TIME_INACT register is set to a value less than the time + * constant of the output data rate. A value of 0 results in an interrupt when + * the output data is less than the value in the THRESH_INACT register. + * @return Inactivity time (scaled at 1 sec/LSB) + * @see ADXL345_RA_TIME_INACT + */ +uint8_t ADXL345::getInactivityTime() { + I2Cdev::readByte(devAddr, ADXL345_RA_TIME_INACT, buffer); + return buffer[0]; +} +/** Set inactivity time. + * @param time Inactivity time (scaled at 1 sec/LSB) + * @see getInctivityTime() + * @see ADXL345_RA_TIME_INACT + */ +void ADXL345::setInactivityTime(uint8_t time) { + I2Cdev::writeByte(devAddr, ADXL345_RA_TIME_INACT, time); +} + +// ACT_INACT_CTL register + +/** Get activity AC/DC coupling. + * A setting of 0 selects dc-coupled operation, and a setting of 1 enables + * ac-coupled operation. In dc-coupled operation, the current acceleration + * magnitude is compared directly with THRESH_ACT and THRESH_INACT to determine + * whether activity or inactivity is detected. + * + * In ac-coupled operation for activity detection, the acceleration value at the + * start of activity detection is taken as a reference value. New samples of + * acceleration are then compared to this reference value, and if the magnitude + * of the difference exceeds the THRESH_ACT value, the device triggers an + * activity interrupt. + * + * Similarly, in ac-coupled operation for inactivity detection, a reference + * value is used for comparison and is updated whenever the device exceeds the + * inactivity threshold. After the reference value is selected, the device + * compares the magnitude of the difference between the reference value and the + * current acceleration with THRESH_INACT. If the difference is less than the + * value in THRESH_INACT for the time in TIME_INACT, the device is considered + * inactive and the inactivity interrupt is triggered. + * + * @return Activity coupling (0 = DC, 1 = AC) + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_AC_BIT + */ +bool ADXL345::getActivityAC() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_AC_BIT, buffer); + return buffer[0]; +} +/** Set activity AC/DC coupling. + * @param enabled Activity AC/DC coupling (TRUE for AC, FALSE for DC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_AC_BIT + */ +void ADXL345::setActivityAC(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_AC_BIT, enabled); +} +/** Get X axis activity monitoring inclusion. + * For all "get[In]Activity*Enabled()" methods: a setting of 1 enables x-, y-, + * or z-axis participation in detecting activity or inactivity. A setting of 0 + * excludes the selected axis from participation. If all axes are excluded, the + * function is disabled. For activity detection, all participating axes are + * logically OR�ed, causing the activity function to trigger when any of the + * participating axes exceeds the threshold. For inactivity detection, all + * participating axes are logically AND�ed, causing the inactivity function to + * trigger only if all participating axes are below the threshold for the + * specified time. + * @return X axis activity monitoring enabled value + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_X_BIT + */ +bool ADXL345::getActivityXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_X_BIT, buffer); + return buffer[0]; +} +/** Set X axis activity monitoring inclusion. + * @param enabled X axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_X_BIT + */ +void ADXL345::setActivityXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_X_BIT, enabled); +} +/** Get Y axis activity monitoring. + * @return Y axis activity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Y_BIT + */ +bool ADXL345::getActivityYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Y_BIT, buffer); + return buffer[0]; +} +/** Set Y axis activity monitoring inclusion. + * @param enabled Y axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Y_BIT + */ +void ADXL345::setActivityYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Y_BIT, enabled); +} +/** Get Z axis activity monitoring. + * @return Z axis activity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Z_BIT + */ +bool ADXL345::getActivityZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Z_BIT, buffer); + return buffer[0]; +} +/** Set Z axis activity monitoring inclusion. + * @param enabled Z axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Z_BIT + */ +void ADXL345::setActivityZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Z_BIT, enabled); +} +/** Get inactivity AC/DC coupling. + * @return Inctivity coupling (0 = DC, 1 = AC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_AC_BIT + */ +bool ADXL345::getInactivityAC() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_AC_BIT, buffer); + return buffer[0]; +} +/** Set inctivity AC/DC coupling. + * @param enabled Inactivity AC/DC coupling (TRUE for AC, FALSE for DC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_AC_BIT + */ +void ADXL345::setInactivityAC(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_AC_BIT, enabled); +} +/** Get X axis inactivity monitoring. + * @return Y axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_X_BIT + */ +bool ADXL345::getInactivityXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_X_BIT, buffer); + return buffer[0]; +} +/** Set X axis activity monitoring inclusion. + * @param enabled X axis inactivity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_X_BIT + */ +void ADXL345::setInactivityXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_X_BIT, enabled); +} +/** Get Y axis inactivity monitoring. + * @return Y axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Y_BIT + */ +bool ADXL345::getInactivityYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Y_BIT, buffer); + return buffer[0]; +} +/** Set Y axis inactivity monitoring inclusion. + * @param enabled Y axis inactivity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Y_BIT + */ +void ADXL345::setInactivityYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Y_BIT, enabled); +} +/** Get Z axis inactivity monitoring. + * @return Z axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Z_BIT + */ +bool ADXL345::getInactivityZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Z_BIT, buffer); + return buffer[0]; +} +/** Set Z axis inactivity monitoring inclusion. + * @param enabled Z axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Z_BIT + */ +void ADXL345::setInactivityZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Z_BIT, enabled); +} + +// THRESH_FF register + +/** Get freefall threshold value. + * The THRESH_FF register is eight bits and holds the threshold value, in + * unsigned format, for free-fall detection. The acceleration on all axes is + * compared with the value in THRESH_FF to determine if a free-fall event + * occurred. The scale factor is 62.5 mg/LSB. Note that a value of 0 mg may + * result in undesirable behavior if the free-fall interrupt is enabled. Values + * between 300 mg and 600 mg (0x05 to 0x09) are recommended. + * @return Freefall threshold value (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_FF + */ +uint8_t ADXL345::getFreefallThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_FF, buffer); + return buffer[0]; +} +/** Set freefall threshold value. + * @param threshold Freefall threshold value (scaled at 62.5 mg/LSB) + * @see getFreefallThreshold() + * @see ADXL345_RA_THRESH_FF + */ +void ADXL345::setFreefallThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_FF, threshold); +} + +// TIME_FF register + +/** Get freefall time value. + * The TIME_FF register is eight bits and stores an unsigned time value + * representing the minimum time that the value of all axes must be less than + * THRESH_FF to generate a free-fall interrupt. The scale factor is 5 ms/LSB. A + * value of 0 may result in undesirable behavior if the free-fall interrupt is + * enabled. Values between 100 ms and 350 ms (0x14 to 0x46) are recommended. + * @return Freefall time value (scaled at 5 ms/LSB) + * @see getFreefallThreshold() + * @see ADXL345_RA_TIME_FF + */ +uint8_t ADXL345::getFreefallTime() { + I2Cdev::readByte(devAddr, ADXL345_RA_TIME_FF, buffer); + return buffer[0]; +} +/** Set freefall time value. + * @param threshold Freefall time value (scaled at 5 ms/LSB) + * @see getFreefallTime() + * @see ADXL345_RA_TIME_FF + */ +void ADXL345::setFreefallTime(uint8_t time) { + I2Cdev::writeByte(devAddr, ADXL345_RA_TIME_FF, time); +} + +// TAP_AXES register + +/** Get double-tap fast-movement suppression. + * Setting the suppress bit suppresses double tap detection if acceleration + * greater than the value in THRESH_TAP is present between taps. See the Tap + * Detection section in the datasheet for more details. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_SUP_BIT + */ +bool ADXL345::getTapAxisSuppress() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_SUP_BIT, buffer); + return buffer[0]; +} +/** Set double-tap fast-movement suppression. + * @param enabled Double-tap fast-movement suppression value + * @see getTapAxisSuppress() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_SUP_BIT + */ +void ADXL345::setTapAxisSuppress(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_SUP_BIT, enabled); +} +/** Get double-tap fast-movement suppression. + * A setting of 1 in the TAP_X enable bit enables x-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_X_BIT + */ +bool ADXL345::getTapAxisXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_X_BIT, buffer); + return buffer[0]; +} +/** Set tap detection X axis inclusion. + * @param enabled X axis tap detection enabled value + * @see getTapAxisXEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_X_BIT + */ +void ADXL345::setTapAxisXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_X_BIT, enabled); +} +/** Get tap detection Y axis inclusion. + * A setting of 1 in the TAP_Y enable bit enables y-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Y_BIT + */ +bool ADXL345::getTapAxisYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Y_BIT, buffer); + return buffer[0]; +} +/** Set tap detection Y axis inclusion. + * @param enabled Y axis tap detection enabled value + * @see getTapAxisYEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Y_BIT + */ +void ADXL345::setTapAxisYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Y_BIT, enabled); +} +/** Get tap detection Z axis inclusion. + * A setting of 1 in the TAP_Z enable bit enables z-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Z_BIT + */ +bool ADXL345::getTapAxisZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Z_BIT, buffer); + return buffer[0]; +} +/** Set tap detection Z axis inclusion. + * @param enabled Z axis tap detection enabled value + * @see getTapAxisZEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Z_BIT + */ +void ADXL345::setTapAxisZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Z_BIT, enabled); +} + +// ACT_TAP_STATUS register + +/** Get X axis activity source flag. + * These bits indicate the first axis involved in a tap or activity event. A + * setting of 1 corresponds to involvement in the event, and a setting of 0 + * corresponds to no involvement. When new data is available, these bits are not + * cleared but are overwritten by the new data. The ACT_TAP_STATUS register + * should be read before clearing the interrupt. Disabling an axis from + * participation clears the corresponding source bit when the next activity or + * single tap/double tap event occurs. + * @return X axis activity source flag + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTX_BIT + */ +bool ADXL345::getActivitySourceX() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTX_BIT, buffer); + return buffer[0]; +} +/** Get Y axis activity source flag. + * @return Y axis activity source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTY_BIT + */ +bool ADXL345::getActivitySourceY() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTY_BIT, buffer); + return buffer[0]; +} +/** Get Z axis activity source flag. + * @return Z axis activity source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTZ_BIT + */ +bool ADXL345::getActivitySourceZ() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTZ_BIT, buffer); + return buffer[0]; +} +/** Get sleep mode flag. + * A setting of 1 in the asleep bit indicates that the part is asleep, and a + * setting of 0 indicates that the part is not asleep. This bit toggles only if + * the device is configured for auto sleep. See the AUTO_SLEEP Bit section of + * the datasheet for more information on autosleep mode. + * @return Sleep mode enabled flag + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ASLEEP_BIT + */ +bool ADXL345::getAsleep() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ASLEEP_BIT, buffer); + return buffer[0]; +} +/** Get X axis tap source flag. + * @return X axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPX_BIT + */ +bool ADXL345::getTapSourceX() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPX_BIT, buffer); + return buffer[0]; +} +/** Get Y axis tap source flag. + * @return Y axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPY_BIT + */ +bool ADXL345::getTapSourceY() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPY_BIT, buffer); + return buffer[0]; +} +/** Get Z axis tap source flag. + * @return Z axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPZ_BIT + */ +bool ADXL345::getTapSourceZ() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPZ_BIT, buffer); + return buffer[0]; +} + +// BW_RATE register + +/** Get low power enabled status. + * A setting of 0 in the LOW_POWER bit selects normal operation, and a setting + * of 1 selects reduced power operation, which has somewhat higher noise (see + * the Power Modes section of the datasheet for details). + * @return Low power enabled status + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_LOWPOWER_BIT + */ +bool ADXL345::getLowPowerEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_LOWPOWER_BIT, buffer); + return buffer[0]; +} +/** Set low power enabled status. + * @see getLowPowerEnabled() + * @param enabled Low power enable setting + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_LOWPOWER_BIT + */ +void ADXL345::setLowPowerEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_LOWPOWER_BIT, enabled); +} +/** Get measurement data rate. + * These bits select the device bandwidth and output data rate (see Table 7 and + * Table 8 in the datasheet for details). The default value is 0x0A, which + * translates to a 100 Hz output data rate. An output data rate should be + * selected that is appropriate for the communication protocol and frequency + * selected. Selecting too high of an output data rate with a low communication + * speed results in samples being discarded. + * @return Data rate (0x0 - 0xF) + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_RATE_BIT + * @see ADXL345_BW_RATE_LENGTH + */ +uint8_t ADXL345::getRate() { + I2Cdev::readBits(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_RATE_BIT, ADXL345_BW_RATE_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement data rate. + * 0x7 = 12.5Hz + * 0x8 = 25Hz, increasing or decreasing by factors of 2, so: + * 0x9 = 50Hz + * 0xA = 100Hz + * @param rate New data rate (0x0 - 0xF) + * @see ADXL345_RATE_100 + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_RATE_BIT + * @see ADXL345_BW_RATE_LENGTH + */ +void ADXL345::setRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_RATE_BIT, ADXL345_BW_RATE_LENGTH, rate); +} + +// POWER_CTL register + +/** Get activity/inactivity serial linkage status. + * A setting of 1 in the link bit with both the activity and inactivity + * functions enabled delays the start of the activity function until + * inactivity is detected. After activity is detected, inactivity detection + * begins, preventing the detection of activity. This bit serially links the + * activity and inactivity functions. When this bit is set to 0, the inactivity + * and activity functions are concurrent. Additional information can be found + * in the Link Mode section of the datasheet. + * + * When clearing the link bit, it is recommended that the part be placed into + * standby mode and then set back to measurement mode with a subsequent write. + * This is done to ensure that the device is properly biased if sleep mode is + * manually disabled; otherwise, the first few samples of data after the link + * bit is cleared may have additional noise, especially if the device was asleep + * when the bit was cleared. + * + * @return Link status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_LINK_BIT + */ +bool ADXL345::getLinkEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_LINK_BIT, buffer); + return buffer[0]; +} +/** Set activity/inactivity serial linkage status. + * @param enabled New link status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_LINK_BIT + */ +void ADXL345::setLinkEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_LINK_BIT, enabled); +} +/** Get auto-sleep enabled status. + * If the link bit is set, a setting of 1 in the AUTO_SLEEP bit enables the + * auto-sleep functionality. In this mode, the ADXL345 auto-matically switches + * to sleep mode if the inactivity function is enabled and inactivity is + * detected (that is, when acceleration is below the THRESH_INACT value for at + * least the time indicated by TIME_INACT). If activity is also enabled, the + * ADXL345 automatically wakes up from sleep after detecting activity and + * returns to operation at the output data rate set in the BW_RATE register. A + * setting of 0 in the AUTO_SLEEP bit disables automatic switching to sleep + * mode. See the description of the Sleep Bit in this section of the datasheet + * for more information on sleep mode. + * + * If the link bit is not set, the AUTO_SLEEP feature is disabled and setting + * the AUTO_SLEEP bit does not have an impact on device operation. Refer to the + * Link Bit section or the Link Mode section for more information on utilization + * of the link feature. + * + * When clearing the AUTO_SLEEP bit, it is recommended that the part be placed + * into standby mode and then set back to measure-ment mode with a subsequent + * write. This is done to ensure that the device is properly biased if sleep + * mode is manually disabled; otherwise, the first few samples of data after the + * AUTO_SLEEP bit is cleared may have additional noise, especially if the device + * was asleep when the bit was cleared. + * + * @return Auto-sleep enabled status + * @see getActivityThreshold() + * @see getInactivityThreshold() + * @see getInactivityTime() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_AUTOSLEEP_BIT + */ +bool ADXL345::getAutoSleepEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_AUTOSLEEP_BIT, buffer); + return buffer[0]; +} +/** Set auto-sleep enabled status. + * @param enabled New auto-sleep status + * @see getAutoSleepEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_AUTOSLEEP_BIT + */ +void ADXL345::setAutoSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_AUTOSLEEP_BIT, enabled); +} +/** Get measurement enabled status. + * A setting of 0 in the measure bit places the part into standby mode, and a + * setting of 1 places the part into measurement mode. The ADXL345 powers up in + * standby mode with minimum power consumption. + * @return Measurement enabled status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_MEASURE_BIT + */ +bool ADXL345::getMeasureEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_MEASURE_BIT, buffer); + return buffer[0]; +} +/** Set measurement enabled status. + * @param enabled Measurement enabled status + * @see getMeasureEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_MEASURE_BIT + */ +void ADXL345::setMeasureEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_MEASURE_BIT, enabled); +} +/** Get sleep mode enabled status. + * A setting of 0 in the sleep bit puts the part into the normal mode of + * operation, and a setting of 1 places the part into sleep mode. Sleep mode + * suppresses DATA_READY, stops transmission of data to FIFO, and switches the + * sampling rate to one specified by the wakeup bits. In sleep mode, only the + * activity function can be used. When the DATA_READY interrupt is suppressed, + * the output data registers (Register 0x32 to Register 0x37) are still updated + * at the sampling rate set by the wakeup bits (D1:D0). + * + * When clearing the sleep bit, it is recommended that the part be placed into + * standby mode and then set back to measurement mode with a subsequent write. + * This is done to ensure that the device is properly biased if sleep mode is + * manually disabled; otherwise, the first few samples of data after the sleep + * bit is cleared may have additional noise, especially if the device was asleep + * when the bit was cleared. + * + * @return Sleep enabled status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +bool ADXL345::getSleepEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode enabled status. + * @param Sleep mode enabled status + * @see getSleepEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +void ADXL345::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_SLEEP_BIT, enabled); +} +/** Get wakeup frequency. + * These bits control the frequency of readings in sleep mode as described in + * Table 20 in the datasheet. (That is, 0 = 8Hz, 1 = 4Hz, 2 = 2Hz, 3 = 1Hz) + * @return Wakeup frequency (0x0 - 0x3, indicating 8/4/2/1Hz respectively) + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +uint8_t ADXL345::getWakeupFrequency() { + I2Cdev::readBits(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_WAKEUP_BIT, ADXL345_PCTL_WAKEUP_LENGTH, buffer); + return buffer[0]; +} +/** Set wakeup frequency. + * @param frequency Wakeup frequency (0x0 - 0x3, indicating 8/4/2/1Hz respectively) + * @see getWakeupFrequency() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +void ADXL345::setWakeupFrequency(uint8_t frequency) { + I2Cdev::writeBits(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_WAKEUP_BIT, ADXL345_PCTL_WAKEUP_LENGTH, frequency); +} + +// INT_ENABLE register + +/** Get DATA_READY interrupt enabled status. + * Setting bits in this register to a value of 1 enables their respective + * functions to generate interrupts, whereas a value of 0 prevents the functions + * from generating interrupts. The DATA_READY, watermark, and overrun bits + * enable only the interrupt output; the functions are always enabled. It is + * recommended that interrupts be configured before enabling their outputs. + * @return DATA_READY interrupt enabled status. + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DATA_READY_BIT + */ +bool ADXL345::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Set DATA_READY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DATA_READY_BIT + */ +void ADXL345::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DATA_READY_BIT, enabled); +} +/** Set SINGLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +bool ADXL345::getIntSingleTapEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set SINGLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +void ADXL345::setIntSingleTapEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_SINGLE_TAP_BIT, enabled); +} +/** Get DOUBLE_TAP interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +bool ADXL345::getIntDoubleTapEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set DOUBLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +void ADXL345::setIntDoubleTapEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DOUBLE_TAP_BIT, enabled); +} +/** Set ACTIVITY interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_ACTIVITY_BIT + */ +bool ADXL345::getIntActivityEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set ACTIVITY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_ACTIVITY_BIT + */ +void ADXL345::setIntActivityEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_ACTIVITY_BIT, enabled); +} +/** Get INACTIVITY interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_INACTIVITY_BIT + */ +bool ADXL345::getIntInactivityEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set INACTIVITY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_INACTIVITY_BIT + */ +void ADXL345::setIntInactivityEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_INACTIVITY_BIT, enabled); +} +/** Get FREE_FALL interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_FREE_FALL_BIT + */ +bool ADXL345::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Set FREE_FALL interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_FREE_FALL_BIT + */ +void ADXL345::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_FREE_FALL_BIT, enabled); +} +/** Get WATERMARK interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_WATERMARK_BIT + */ +bool ADXL345::getIntWatermarkEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Set WATERMARK interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_WATERMARK_BIT + */ +void ADXL345::setIntWatermarkEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_WATERMARK_BIT, enabled); +} +/** Get OVERRUN interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_OVERRUN_BIT + */ +bool ADXL345::getIntOverrunEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} +/** Set OVERRUN interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_OVERRUN_BIT + */ +void ADXL345::setIntOverrunEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_OVERRUN_BIT, enabled); +} + +// INT_MAP register + +/** Get DATA_READY interrupt pin. + * Any bits set to 0 in this register send their respective interrupts to the + * INT1 pin, whereas bits set to 1 send their respective interrupts to the INT2 + * pin. All selected interrupts for a given pin are OR'ed. + * @return Interrupt pin setting + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DATA_READY_BIT + */ +uint8_t ADXL345::getIntDataReadyPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Set DATA_READY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DATA_READY_BIT + */ +void ADXL345::setIntDataReadyPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DATA_READY_BIT, pin); +} +/** Get SINGLE_TAP interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +uint8_t ADXL345::getIntSingleTapPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set SINGLE_TAP interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +void ADXL345::setIntSingleTapPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_SINGLE_TAP_BIT, pin); +} +/** Get DOUBLE_TAP interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +uint8_t ADXL345::getIntDoubleTapPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set DOUBLE_TAP interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +void ADXL345::setIntDoubleTapPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DOUBLE_TAP_BIT, pin); +} +/** Get ACTIVITY interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_ACTIVITY_BIT + */ +uint8_t ADXL345::getIntActivityPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set ACTIVITY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_ACTIVITY_BIT + */ +void ADXL345::setIntActivityPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_ACTIVITY_BIT, pin); +} +/** Get INACTIVITY interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_INACTIVITY_BIT + */ +uint8_t ADXL345::getIntInactivityPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set INACTIVITY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_INACTIVITY_BIT + */ +void ADXL345::setIntInactivityPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_INACTIVITY_BIT, pin); +} +/** Get FREE_FALL interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_FREE_FALL_BIT + */ +uint8_t ADXL345::getIntFreefallPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Set FREE_FALL interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_FREE_FALL_BIT + */ +void ADXL345::setIntFreefallPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_FREE_FALL_BIT, pin); +} +/** Get WATERMARK interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_WATERMARK_BIT + */ +uint8_t ADXL345::getIntWatermarkPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Set WATERMARK interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_WATERMARK_BIT + */ +void ADXL345::setIntWatermarkPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_WATERMARK_BIT, pin); +} +/** Get OVERRUN interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_OVERRUN_BIT + */ +uint8_t ADXL345::getIntOverrunPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} +/** Set OVERRUN interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_OVERRUN_BIT + */ +void ADXL345::setIntOverrunPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_OVERRUN_BIT, pin); +} + +// INT_SOURCE register + +/** Get DATA_READY interrupt source flag. + * Bits set to 1 in this register indicate that their respective functions have + * triggered an event, whereas a value of 0 indicates that the corresponding + * event has not occurred. The DATA_READY, watermark, and overrun bits are + * always set if the corresponding events occur, regardless of the INT_ENABLE + * register settings, and are cleared by reading data from the DATAX, DATAY, and + * DATAZ registers. The DATA_READY and watermark bits may require multiple + * reads, as indicated in the FIFO mode descriptions in the FIFO section. Other + * bits, and the corresponding interrupts, are cleared by reading the INT_SOURCE + * register. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_DATA_READY_BIT + */ +uint8_t ADXL345::getIntDataReadySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Get SINGLE_TAP interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +uint8_t ADXL345::getIntSingleTapSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Get DOUBLE_TAP interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +uint8_t ADXL345::getIntDoubleTapSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Get ACTIVITY interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_ACTIVITY_BIT + */ +uint8_t ADXL345::getIntActivitySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Get INACTIVITY interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_INACTIVITY_BIT + */ +uint8_t ADXL345::getIntInactivitySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Get FREE_FALL interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_FREE_FALL_BIT + */ +uint8_t ADXL345::getIntFreefallSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Get WATERMARK interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_WATERMARK_BIT + */ +uint8_t ADXL345::getIntWatermarkSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Get OVERRUN interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_OVERRUN_BIT + */ +uint8_t ADXL345::getIntOverrunSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} + +// DATA_FORMAT register + +/** Get self-test force enabled. + * A setting of 1 in the SELF_TEST bit applies a self-test force to the sensor, + * causing a shift in the output data. A value of 0 disables the self-test + * force. + * @return Self-test force enabled setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +uint8_t ADXL345::getSelfTestEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SELFTEST_BIT, buffer); + return buffer[0]; +} +/** Set self-test force enabled. + * @param enabled New self-test force enabled setting + * @see getSelfTestEnabled() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +void ADXL345::setSelfTestEnabled(uint8_t enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SELFTEST_BIT, enabled); +} +/** Get SPI mode setting. + * A value of 1 in the SPI bit sets the device to 3-wire SPI mode, and a value + * of 0 sets the device to 4-wire SPI mode. + * @return SPI mode setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +uint8_t ADXL345::getSPIMode() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SPIMODE_BIT, buffer); + return buffer[0]; +} +/** Set SPI mode setting. + * @param mode New SPI mode setting + * @see getSPIMode() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +void ADXL345::setSPIMode(uint8_t mode) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SPIMODE_BIT, mode); +} +/** Get interrupt mode setting. + * A value of 0 in the INT_INVERT bit sets the interrupts to active high, and a + * value of 1 sets the interrupts to active low. + * @return Interrupt mode setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_INTMODE_BIT + */ +uint8_t ADXL345::getInterruptMode() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_INTMODE_BIT, buffer); + return buffer[0]; +} +/** Set interrupt mode setting. + * @param mode New interrupt mode setting + * @see getInterruptMode() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_INTMODE_BIT + */ +void ADXL345::setInterruptMode(uint8_t mode) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_INTMODE_BIT, mode); +} +/** Get full resolution mode setting. + * When this bit is set to a value of 1, the device is in full resolution mode, + * where the output resolution increases with the g range set by the range bits + * to maintain a 4 mg/LSB scale factor. When the FULL_RES bit is set to 0, the + * device is in 10-bit mode, and the range bits determine the maximum g range + * and scale factor. + * @return Full resolution enabled setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_FULL_RES_BIT + */ +uint8_t ADXL345::getFullResolution() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_FULL_RES_BIT, buffer); + return buffer[0]; +} +/** Set full resolution mode setting. + * @param resolution New full resolution enabled setting + * @see getFullResolution() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_FULL_RES_BIT + */ +void ADXL345::setFullResolution(uint8_t resolution) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_FULL_RES_BIT, resolution); +} +/** Get data justification mode setting. + * A setting of 1 in the justify bit selects left-justified (MSB) mode, and a + * setting of 0 selects right-justified mode with sign extension. + * @return Data justification mode + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_JUSTIFY_BIT + */ +uint8_t ADXL345::getDataJustification() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_JUSTIFY_BIT, buffer); + return buffer[0]; +} +/** Set data justification mode setting. + * @param justification New data justification mode + * @see getDataJustification() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_JUSTIFY_BIT + */ +void ADXL345::setDataJustification(uint8_t justification) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_JUSTIFY_BIT, justification); +} +/** Get data range setting. + * These bits set the g range as described in Table 21. (That is, 0x0 - 0x3 to + * indicate 2g/4g/8g/16g respectively) + * @return Range value (0x0 - 0x3 for 2g/4g/8g/16g) + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_RANGE_BIT + * @see ADXL345_FORMAT_RANGE_LENGTH + */ +uint8_t ADXL345::getRange() { + I2Cdev::readBits(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_RANGE_BIT, ADXL345_FORMAT_RANGE_LENGTH, buffer); + return buffer[0]; +} +/** Set data range setting. + * @param range Range value (0x0 - 0x3 for 2g/4g/8g/16g) + * @see getRange() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_RANGE_BIT + * @see ADXL345_FORMAT_RANGE_LENGTH + */ +void ADXL345::setRange(uint8_t range) { + I2Cdev::writeBits(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_RANGE_BIT, ADXL345_FORMAT_RANGE_LENGTH, range); +} + +// DATA* registers + +/** Get 3-axis accleration measurements. + * These six bytes (Register 0x32 to Register 0x37) are eight bits each and hold + * the output data for each axis. Register 0x32 and Register 0x33 hold the + * output data for the x-axis, Register 0x34 and Register 0x35 hold the output + * data for the y-axis, and Register 0x36 and Register 0x37 hold the output data + * for the z-axis. The output data is twos complement, with DATAx0 as the least + * significant byte and DATAx1 as the most significant byte, where x represent + * X, Y, or Z. The DATA_FORMAT register (Address 0x31) controls the format of + * the data. It is recommended that a multiple-byte read of all registers be + * performed to prevent a change in data between reads of sequential registers. + * + * The DATA_FORMAT register controls the presentation of data to Register 0x32 + * through Register 0x37. All data, except that for the +/-16 g range, must be + * clipped to avoid rollover. + * + * @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 ADXL345_RA_DATAX0 + */ +void ADXL345::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAX0, 6, buffer); + *x = (((int16_t)buffer[1]) << 8) | buffer[0]; + *y = (((int16_t)buffer[3]) << 8) | buffer[2]; + *z = (((int16_t)buffer[5]) << 8) | buffer[4]; +} +/** Get X-axis accleration measurement. + * @return 16-bit signed X-axis acceleration value + * @see ADXL345_RA_DATAX0 + */ +int16_t ADXL345::getAccelerationX() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAX0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} +/** Get Y-axis accleration measurement. + * @return 16-bit signed Y-axis acceleration value + * @see ADXL345_RA_DATAY0 + */ +int16_t ADXL345::getAccelerationY() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAY0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} +/** Get Z-axis accleration measurement. + * @return 16-bit signed Z-axis acceleration value + * @see ADXL345_RA_DATAZ0 + */ +int16_t ADXL345::getAccelerationZ() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAZ0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} + +// FIFO_CTL register + +/** Get FIFO mode. + * These bits set the FIFO mode, as described in Table 22. That is: + * + * 0x0 = Bypass (FIFO is bypassed.) + * + * 0x1 = FIFO (FIFO collects up to 32 values and then stops collecting data, + * collecting new data only when FIFO is not full.) + * + * 0x2 = Stream (FIFO holds the last 32 data values. When FIFO is full, the + * oldest data is overwritten with newer data.) + * + * 0x3 = Trigger (When triggered by the trigger bit, FIFO holds the last data + * samples before the trigger event and then continues to collect data + * until full. New data is collected only when FIFO is not full.) + * + * @return Curent FIFO mode + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_MODE_BIT + * @see ADXL345_FIFO_MODE_LENGTH + */ +uint8_t ADXL345::getFIFOMode() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_MODE_BIT, ADXL345_FIFO_MODE_LENGTH, buffer); + return buffer[0]; +} +/** Set FIFO mode. + * @param mode New FIFO mode + * @see getFIFOMode() + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_MODE_BIT + * @see ADXL345_FIFO_MODE_LENGTH + */ +void ADXL345::setFIFOMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_MODE_BIT, ADXL345_FIFO_MODE_LENGTH, mode); +} +/** Get FIFO trigger interrupt setting. + * A value of 0 in the trigger bit links the trigger event of trigger mode to + * INT1, and a value of 1 links the trigger event to INT2. + * @return Current FIFO trigger interrupt setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_TRIGGER_BIT + */ +uint8_t ADXL345::getFIFOTriggerInterruptPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_TRIGGER_BIT, buffer); + return buffer[0]; +} +/** Set FIFO trigger interrupt pin setting. + * @param interrupt New FIFO trigger interrupt pin setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_TRIGGER_BIT + */ +void ADXL345::setFIFOTriggerInterruptPin(uint8_t interrupt) { + I2Cdev::writeBit(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_TRIGGER_BIT, interrupt); +} +/** Get FIFO samples setting. + * The function of these bits depends on the FIFO mode selected (see Table 23). + * Entering a value of 0 in the samples bits immediately sets the watermark + * status bit in the INT_SOURCE register, regardless of which FIFO mode is + * selected. Undesirable operation may occur if a value of 0 is used for the + * samples bits when trigger mode is used. + * + * MODE | EFFECT + * --------+------------------------------------------------------------------- + * Bypass | None. + * FIFO | FIFO entries needed to trigger a watermark interrupt. + * Stream | FIFO entries needed to trigger a watermark interrupt. + * Trigger | Samples are retained in the FIFO buffer before a trigger event. + * + * @return Current FIFO samples setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_SAMPLES_BIT + * @see ADXL345_FIFO_SAMPLES_LENGTH + */ +uint8_t ADXL345::getFIFOSamples() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_SAMPLES_BIT, ADXL345_FIFO_SAMPLES_LENGTH, buffer); + return buffer[0]; +} +/** Set FIFO samples setting. + * @param size New FIFO samples setting (impact depends on FIFO mode setting) + * @see getFIFOSamples() + * @see getFIFOMode() + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_SAMPLES_BIT + * @see ADXL345_FIFO_SAMPLES_LENGTH + */ +void ADXL345::setFIFOSamples(uint8_t size) { + I2Cdev::writeBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_SAMPLES_BIT, ADXL345_FIFO_SAMPLES_LENGTH, size); +} + +// FIFO_STATUS register + +/** Get FIFO trigger occurred status. + * A 1 in the FIFO_TRIG bit corresponds to a trigger event occurring, and a 0 + * means that a FIFO trigger event has not occurred. + * @return FIFO trigger occurred status + * @see ADXL345_RA_FIFO_STATUS + * @see ADXL345_FIFOSTAT_TRIGGER_BIT + */ +bool ADXL345::getFIFOTriggerOccurred() { + I2Cdev::readBit(devAddr, ADXL345_RA_FIFO_STATUS, ADXL345_FIFOSTAT_TRIGGER_BIT, buffer); + return buffer[0]; +} +/** Get FIFO length. + * These bits report how many data values are stored in FIFO. Access to collect + * the data from FIFO is provided through the DATAX, DATAY, and DATAZ registers. + * FIFO reads must be done in burst or multiple-byte mode because each FIFO + * level is cleared after any read (single- or multiple-byte) of FIFO. FIFO + * stores a maximum of 32 entries, which equates to a maximum of 33 entries + * available at any given time because an additional entry is available at the + * output filter of the I2Cdev:: + * @return Current FIFO length + * @see ADXL345_RA_FIFO_STATUS + * @see ADXL345_FIFOSTAT_LENGTH_BIT + * @see ADXL345_FIFOSTAT_LENGTH_LENGTH + */ +uint8_t ADXL345::getFIFOLength() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_STATUS, ADXL345_FIFOSTAT_LENGTH_BIT, ADXL345_FIFOSTAT_LENGTH_LENGTH, buffer); + return buffer[0]; +} diff --git a/firmware/lib/imu/ADXL345.h b/firmware/lib/imu/ADXL345.h new file mode 100644 index 0000000..b610caf --- /dev/null +++ b/firmware/lib/imu/ADXL345.h @@ -0,0 +1,361 @@ +// I2Cdev library collection - ADXL345 I2C device class header file +// Based on Analog Devices ADXL345 datasheet rev. C, 5/2011 +// 7/31/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#ifndef _ADXL345_H_ +#define _ADXL345_H_ + +#include "I2Cdev.h" + +#define ADXL345_ADDRESS_ALT_LOW 0x53 // alt address pin low (GND) +#define ADXL345_ADDRESS_ALT_HIGH 0x1D // alt address pin high (VCC) +#define ADXL345_DEFAULT_ADDRESS ADXL345_ADDRESS_ALT_LOW + +#define ADXL345_RA_DEVID 0x00 +#define ADXL345_RA_RESERVED1 0x01 +#define ADXL345_RA_THRESH_TAP 0x1D +#define ADXL345_RA_OFSX 0x1E +#define ADXL345_RA_OFSY 0x1F +#define ADXL345_RA_OFSZ 0x20 +#define ADXL345_RA_DUR 0x21 +#define ADXL345_RA_LATENT 0x22 +#define ADXL345_RA_WINDOW 0x23 +#define ADXL345_RA_THRESH_ACT 0x24 +#define ADXL345_RA_THRESH_INACT 0x25 +#define ADXL345_RA_TIME_INACT 0x26 +#define ADXL345_RA_ACT_INACT_CTL 0x27 +#define ADXL345_RA_THRESH_FF 0x28 +#define ADXL345_RA_TIME_FF 0x29 +#define ADXL345_RA_TAP_AXES 0x2A +#define ADXL345_RA_ACT_TAP_STATUS 0x2B +#define ADXL345_RA_BW_RATE 0x2C +#define ADXL345_RA_POWER_CTL 0x2D +#define ADXL345_RA_INT_ENABLE 0x2E +#define ADXL345_RA_INT_MAP 0x2F +#define ADXL345_RA_INT_SOURCE 0x30 +#define ADXL345_RA_DATA_FORMAT 0x31 +#define ADXL345_RA_DATAX0 0x32 +#define ADXL345_RA_DATAX1 0x33 +#define ADXL345_RA_DATAY0 0x34 +#define ADXL345_RA_DATAY1 0x35 +#define ADXL345_RA_DATAZ0 0x36 +#define ADXL345_RA_DATAZ1 0x37 +#define ADXL345_RA_FIFO_CTL 0x38 +#define ADXL345_RA_FIFO_STATUS 0x39 + +#define ADXL345_AIC_ACT_AC_BIT 7 +#define ADXL345_AIC_ACT_X_BIT 6 +#define ADXL345_AIC_ACT_Y_BIT 5 +#define ADXL345_AIC_ACT_Z_BIT 4 +#define ADXL345_AIC_INACT_AC_BIT 3 +#define ADXL345_AIC_INACT_X_BIT 2 +#define ADXL345_AIC_INACT_Y_BIT 1 +#define ADXL345_AIC_INACT_Z_BIT 0 + +#define ADXL345_TAPAXIS_SUP_BIT 3 +#define ADXL345_TAPAXIS_X_BIT 2 +#define ADXL345_TAPAXIS_Y_BIT 1 +#define ADXL345_TAPAXIS_Z_BIT 0 + +#define ADXL345_TAPSTAT_ACTX_BIT 6 +#define ADXL345_TAPSTAT_ACTY_BIT 5 +#define ADXL345_TAPSTAT_ACTZ_BIT 4 +#define ADXL345_TAPSTAT_ASLEEP_BIT 3 +#define ADXL345_TAPSTAT_TAPX_BIT 2 +#define ADXL345_TAPSTAT_TAPY_BIT 1 +#define ADXL345_TAPSTAT_TAPZ_BIT 0 + +#define ADXL345_BW_LOWPOWER_BIT 4 +#define ADXL345_BW_RATE_BIT 3 +#define ADXL345_BW_RATE_LENGTH 4 + +#define ADXL345_RATE_3200 0b1111 +#define ADXL345_RATE_1600 0b1110 +#define ADXL345_RATE_800 0b1101 +#define ADXL345_RATE_400 0b1100 +#define ADXL345_RATE_200 0b1011 +#define ADXL345_RATE_100 0b1010 +#define ADXL345_RATE_50 0b1001 +#define ADXL345_RATE_25 0b1000 +#define ADXL345_RATE_12P5 0b0111 +#define ADXL345_RATE_6P25 0b0110 +#define ADXL345_RATE_3P13 0b0101 +#define ADXL345_RATE_1P56 0b0100 +#define ADXL345_RATE_0P78 0b0011 +#define ADXL345_RATE_0P39 0b0010 +#define ADXL345_RATE_0P20 0b0001 +#define ADXL345_RATE_0P10 0b0000 + +#define ADXL345_PCTL_LINK_BIT 5 +#define ADXL345_PCTL_AUTOSLEEP_BIT 4 +#define ADXL345_PCTL_MEASURE_BIT 3 +#define ADXL345_PCTL_SLEEP_BIT 2 +#define ADXL345_PCTL_WAKEUP_BIT 1 +#define ADXL345_PCTL_WAKEUP_LENGTH 2 + +#define ADXL345_WAKEUP_8HZ 0b00 +#define ADXL345_WAKEUP_4HZ 0b01 +#define ADXL345_WAKEUP_2HZ 0b10 +#define ADXL345_WAKEUP_1HZ 0b11 + +#define ADXL345_INT_DATA_READY_BIT 7 +#define ADXL345_INT_SINGLE_TAP_BIT 6 +#define ADXL345_INT_DOUBLE_TAP_BIT 5 +#define ADXL345_INT_ACTIVITY_BIT 4 +#define ADXL345_INT_INACTIVITY_BIT 3 +#define ADXL345_INT_FREE_FALL_BIT 2 +#define ADXL345_INT_WATERMARK_BIT 1 +#define ADXL345_INT_OVERRUN_BIT 0 + +#define ADXL345_FORMAT_SELFTEST_BIT 7 +#define ADXL345_FORMAT_SPIMODE_BIT 6 +#define ADXL345_FORMAT_INTMODE_BIT 5 +#define ADXL345_FORMAT_FULL_RES_BIT 3 +#define ADXL345_FORMAT_JUSTIFY_BIT 2 +#define ADXL345_FORMAT_RANGE_BIT 1 +#define ADXL345_FORMAT_RANGE_LENGTH 2 + +#define ADXL345_RANGE_2G 0b00 +#define ADXL345_RANGE_4G 0b01 +#define ADXL345_RANGE_8G 0b10 +#define ADXL345_RANGE_16G 0b11 + +#define ADXL345_FIFO_MODE_BIT 7 +#define ADXL345_FIFO_MODE_LENGTH 2 +#define ADXL345_FIFO_TRIGGER_BIT 5 +#define ADXL345_FIFO_SAMPLES_BIT 4 +#define ADXL345_FIFO_SAMPLES_LENGTH 5 + +#define ADXL345_FIFO_MODE_BYPASS 0b00 +#define ADXL345_FIFO_MODE_FIFO 0b01 +#define ADXL345_FIFO_MODE_STREAM 0b10 +#define ADXL345_FIFO_MODE_TRIGGER 0b11 + +#define ADXL345_FIFOSTAT_TRIGGER_BIT 7 +#define ADXL345_FIFOSTAT_LENGTH_BIT 5 +#define ADXL345_FIFOSTAT_LENGTH_LENGTH 6 + +class ADXL345 { + public: + ADXL345(); + ADXL345(uint8_t address); + + void initialize(); + bool testConnection(); + + // DEVID register + uint8_t getDeviceID(); + + // THRESH_TAP register + uint8_t getTapThreshold(); + void setTapThreshold(uint8_t threshold); + + // OFS* registers + void getOffset(int8_t* x, int8_t* y, int8_t* z); + void setOffset(int8_t x, int8_t y, int8_t z); + int8_t getOffsetX(); + void setOffsetX(int8_t x); + int8_t getOffsetY(); + void setOffsetY(int8_t y); + int8_t getOffsetZ(); + void setOffsetZ(int8_t z); + + // DUR register + uint8_t getTapDuration(); + void setTapDuration(uint8_t duration); + + // LATENT register + uint8_t getDoubleTapLatency(); + void setDoubleTapLatency(uint8_t latency); + + // WINDOW register + uint8_t getDoubleTapWindow(); + void setDoubleTapWindow(uint8_t window); + + // THRESH_ACT register + uint8_t getActivityThreshold(); + void setActivityThreshold(uint8_t threshold); + + // THRESH_INACT register + uint8_t getInactivityThreshold(); + void setInactivityThreshold(uint8_t threshold); + + // TIME_INACT register + uint8_t getInactivityTime(); + void setInactivityTime(uint8_t time); + + // ACT_INACT_CTL register + bool getActivityAC(); + void setActivityAC(bool enabled); + bool getActivityXEnabled(); + void setActivityXEnabled(bool enabled); + bool getActivityYEnabled(); + void setActivityYEnabled(bool enabled); + bool getActivityZEnabled(); + void setActivityZEnabled(bool enabled); + bool getInactivityAC(); + void setInactivityAC(bool enabled); + bool getInactivityXEnabled(); + void setInactivityXEnabled(bool enabled); + bool getInactivityYEnabled(); + void setInactivityYEnabled(bool enabled); + bool getInactivityZEnabled(); + void setInactivityZEnabled(bool enabled); + + // THRESH_FF register + uint8_t getFreefallThreshold(); + void setFreefallThreshold(uint8_t threshold); + + // TIME_FF register + uint8_t getFreefallTime(); + void setFreefallTime(uint8_t time); + + // TAP_AXES register + bool getTapAxisSuppress(); + void setTapAxisSuppress(bool enabled); + bool getTapAxisXEnabled(); + void setTapAxisXEnabled(bool enabled); + bool getTapAxisYEnabled(); + void setTapAxisYEnabled(bool enabled); + bool getTapAxisZEnabled(); + void setTapAxisZEnabled(bool enabled); + + // ACT_TAP_STATUS register + bool getActivitySourceX(); + bool getActivitySourceY(); + bool getActivitySourceZ(); + bool getAsleep(); + bool getTapSourceX(); + bool getTapSourceY(); + bool getTapSourceZ(); + + // BW_RATE register + bool getLowPowerEnabled(); + void setLowPowerEnabled(bool enabled); + uint8_t getRate(); + void setRate(uint8_t rate); + + // POWER_CTL register + bool getLinkEnabled(); + void setLinkEnabled(bool enabled); + bool getAutoSleepEnabled(); + void setAutoSleepEnabled(bool enabled); + bool getMeasureEnabled(); + void setMeasureEnabled(bool enabled); + bool getSleepEnabled(); + void setSleepEnabled(bool enabled); + uint8_t getWakeupFrequency(); + void setWakeupFrequency(uint8_t frequency); + + // INT_ENABLE register + bool getIntDataReadyEnabled(); + void setIntDataReadyEnabled(bool enabled); + bool getIntSingleTapEnabled(); + void setIntSingleTapEnabled(bool enabled); + bool getIntDoubleTapEnabled(); + void setIntDoubleTapEnabled(bool enabled); + bool getIntActivityEnabled(); + void setIntActivityEnabled(bool enabled); + bool getIntInactivityEnabled(); + void setIntInactivityEnabled(bool enabled); + bool getIntFreefallEnabled(); + void setIntFreefallEnabled(bool enabled); + bool getIntWatermarkEnabled(); + void setIntWatermarkEnabled(bool enabled); + bool getIntOverrunEnabled(); + void setIntOverrunEnabled(bool enabled); + + // INT_MAP register + uint8_t getIntDataReadyPin(); + void setIntDataReadyPin(uint8_t pin); + uint8_t getIntSingleTapPin(); + void setIntSingleTapPin(uint8_t pin); + uint8_t getIntDoubleTapPin(); + void setIntDoubleTapPin(uint8_t pin); + uint8_t getIntActivityPin(); + void setIntActivityPin(uint8_t pin); + uint8_t getIntInactivityPin(); + void setIntInactivityPin(uint8_t pin); + uint8_t getIntFreefallPin(); + void setIntFreefallPin(uint8_t pin); + uint8_t getIntWatermarkPin(); + void setIntWatermarkPin(uint8_t pin); + uint8_t getIntOverrunPin(); + void setIntOverrunPin(uint8_t pin); + + // INT_SOURCE register + uint8_t getIntDataReadySource(); + uint8_t getIntSingleTapSource(); + uint8_t getIntDoubleTapSource(); + uint8_t getIntActivitySource(); + uint8_t getIntInactivitySource(); + uint8_t getIntFreefallSource(); + uint8_t getIntWatermarkSource(); + uint8_t getIntOverrunSource(); + + // DATA_FORMAT register + uint8_t getSelfTestEnabled(); + void setSelfTestEnabled(uint8_t enabled); + uint8_t getSPIMode(); + void setSPIMode(uint8_t mode); + uint8_t getInterruptMode(); + void setInterruptMode(uint8_t mode); + uint8_t getFullResolution(); + void setFullResolution(uint8_t resolution); + uint8_t getDataJustification(); + void setDataJustification(uint8_t justification); + uint8_t getRange(); + void setRange(uint8_t range); + + // DATA* registers + void getAcceleration(int16_t* x, int16_t* y, int16_t* z); + int16_t getAccelerationX(); + int16_t getAccelerationY(); + int16_t getAccelerationZ(); + + // FIFO_CTL register + uint8_t getFIFOMode(); + void setFIFOMode(uint8_t mode); + uint8_t getFIFOTriggerInterruptPin(); + void setFIFOTriggerInterruptPin(uint8_t interrupt); + uint8_t getFIFOSamples(); + void setFIFOSamples(uint8_t size); + + // FIFO_STATUS register + bool getFIFOTriggerOccurred(); + uint8_t getFIFOLength(); + + private: + uint8_t devAddr; + uint8_t buffer[6]; +}; + +#endif /* _ADXL345_H_ */ diff --git a/firmware/lib/imu/HMC5883L.cpp b/firmware/lib/imu/HMC5883L.cpp new file mode 100644 index 0000000..29d8fb5 --- /dev/null +++ b/firmware/lib/imu/HMC5883L.cpp @@ -0,0 +1,365 @@ +// I2Cdev library collection - HMC5883L I2C device class +// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B) +// 6/12/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-12 - fixed swapped Y/Z axes +// 2011-08-22 - small Doxygen comment fixes +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "HMC5883L.h" + +/** Default constructor, uses default I2C address. + * @see HMC5883L_DEFAULT_ADDRESS + */ +HMC5883L::HMC5883L() { + devAddr = HMC5883L_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see HMC5883L_DEFAULT_ADDRESS + * @see HMC5883L_ADDRESS + */ +HMC5883L::HMC5883L(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will prepare the magnetometer with default settings, ready for single- + * use mode (very low power requirements). Default settings include 8-sample + * averaging, 15 Hz data output rate, normal measurement bias, a,d 1090 gain (in + * terms of LSB/Gauss). Be sure to adjust any settings you need specifically + * after initialization, especially the gain settings if you happen to be seeing + * a lot of -4096 values (see the datasheet for mor information). + */ +void HMC5883L::initialize() { + // write CONFIG_A register + I2Cdev::writeByte(devAddr, HMC5883L_RA_CONFIG_A, + (HMC5883L_AVERAGING_8 << (HMC5883L_CRA_AVERAGE_BIT - HMC5883L_CRA_AVERAGE_LENGTH + 1)) | + (HMC5883L_RATE_15 << (HMC5883L_CRA_RATE_BIT - HMC5883L_CRA_RATE_LENGTH + 1)) | + (HMC5883L_BIAS_NORMAL << (HMC5883L_CRA_BIAS_BIT - HMC5883L_CRA_BIAS_LENGTH + 1))); + + // write CONFIG_B register + setGain(HMC5883L_GAIN_1090); + + // write MODE register + setMode(HMC5883L_MODE_SINGLE); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool HMC5883L::testConnection() { + if (I2Cdev::readBytes(devAddr, HMC5883L_RA_ID_A, 3, buffer) == 3) { + return (buffer[0] == 'H' && buffer[1] == '4' && buffer[2] == '3'); + } + return false; +} + +// CONFIG_A register + +/** Get number of samples averaged per measurement. + * @return Current samples averaged per measurement (0-3 for 1/2/4/8 respectively) + * @see HMC5883L_AVERAGING_8 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_AVERAGE_BIT + * @see HMC5883L_CRA_AVERAGE_LENGTH + */ +uint8_t HMC5883L::getSampleAveraging() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, buffer); + return buffer[0]; +} +/** Set number of samples averaged per measurement. + * @param averaging New samples averaged per measurement setting(0-3 for 1/2/4/8 respectively) + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_AVERAGE_BIT + * @see HMC5883L_CRA_AVERAGE_LENGTH + */ +void HMC5883L::setSampleAveraging(uint8_t averaging) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, averaging); +} +/** Get data output rate value. + * The Table below shows all selectable output rates in continuous measurement + * mode. All three channels shall be measured within a given output rate. Other + * output rates with maximum rate of 160 Hz can be achieved by monitoring DRDY + * interrupt pin in single measurement mode. + * + * Value | Typical Data Output Rate (Hz) + * ------+------------------------------ + * 0 | 0.75 + * 1 | 1.5 + * 2 | 3 + * 3 | 7.5 + * 4 | 15 (Default) + * 5 | 30 + * 6 | 75 + * 7 | Not used + * + * @return Current rate of data output to registers + * @see HMC5883L_RATE_15 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_RATE_BIT + * @see HMC5883L_CRA_RATE_LENGTH + */ +uint8_t HMC5883L::getDataRate() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, buffer); + return buffer[0]; +} +/** Set data output rate value. + * @param rate Rate of data output to registers + * @see getDataRate() + * @see HMC5883L_RATE_15 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_RATE_BIT + * @see HMC5883L_CRA_RATE_LENGTH + */ +void HMC5883L::setDataRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, rate); +} +/** Get measurement bias value. + * @return Current bias value (0-2 for normal/positive/negative respectively) + * @see HMC5883L_BIAS_NORMAL + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_BIAS_BIT + * @see HMC5883L_CRA_BIAS_LENGTH + */ +uint8_t HMC5883L::getMeasurementBias() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement bias value. + * @param bias New bias value (0-2 for normal/positive/negative respectively) + * @see HMC5883L_BIAS_NORMAL + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_BIAS_BIT + * @see HMC5883L_CRA_BIAS_LENGTH + */ +void HMC5883L::setMeasurementBias(uint8_t bias) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, bias); +} + +// CONFIG_B register + +/** Get magnetic field gain value. + * The table below shows nominal gain settings. Use the "Gain" column to convert + * counts to Gauss. Choose a lower gain value (higher GN#) when total field + * strength causes overflow in one of the data output registers (saturation). + * The data output range for all settings is 0xF800-0x07FF (-2048 - 2047). + * + * Value | Field Range | Gain (LSB/Gauss) + * ------+-------------+----------------- + * 0 | +/- 0.88 Ga | 1370 + * 1 | +/- 1.3 Ga | 1090 (Default) + * 2 | +/- 1.9 Ga | 820 + * 3 | +/- 2.5 Ga | 660 + * 4 | +/- 4.0 Ga | 440 + * 5 | +/- 4.7 Ga | 390 + * 6 | +/- 5.6 Ga | 330 + * 7 | +/- 8.1 Ga | 230 + * + * @return Current magnetic field gain value + * @see HMC5883L_GAIN_1090 + * @see HMC5883L_RA_CONFIG_B + * @see HMC5883L_CRB_GAIN_BIT + * @see HMC5883L_CRB_GAIN_LENGTH + */ +uint8_t HMC5883L::getGain() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_B, HMC5883L_CRB_GAIN_BIT, HMC5883L_CRB_GAIN_LENGTH, buffer); + return buffer[0]; +} +/** Set magnetic field gain value. + * @param gain New magnetic field gain value + * @see getGain() + * @see HMC5883L_RA_CONFIG_B + * @see HMC5883L_CRB_GAIN_BIT + * @see HMC5883L_CRB_GAIN_LENGTH + */ +void HMC5883L::setGain(uint8_t gain) { + // use this method to guarantee that bits 4-0 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5883L_RA_CONFIG_B, gain << (HMC5883L_CRB_GAIN_BIT - HMC5883L_CRB_GAIN_LENGTH + 1)); +} + +// MODE register + +/** Get measurement mode. + * In continuous-measurement mode, the device continuously performs measurements + * and places the result in the data register. RDY goes high when new data is + * placed in all three registers. After a power-on or a write to the mode or + * configuration register, the first measurement set is available from all three + * data output registers after a period of 2/fDO and subsequent measurements are + * available at a frequency of fDO, where fDO is the frequency of data output. + * + * When single-measurement mode (default) is selected, device performs a single + * measurement, sets RDY high and returned to idle mode. Mode register returns + * to idle mode bit values. The measurement remains in the data output register + * and RDY remains high until the data output register is read or another + * measurement is performed. + * + * @return Current measurement mode + * @see HMC5883L_MODE_CONTINUOUS + * @see HMC5883L_MODE_SINGLE + * @see HMC5883L_MODE_IDLE + * @see HMC5883L_RA_MODE + * @see HMC5883L_MODEREG_BIT + * @see HMC5883L_MODEREG_LENGTH + */ +uint8_t HMC5883L::getMode() { + I2Cdev::readBits(devAddr, HMC5883L_RA_MODE, HMC5883L_MODEREG_BIT, HMC5883L_MODEREG_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement mode. + * @param newMode New measurement mode + * @see getMode() + * @see HMC5883L_MODE_CONTINUOUS + * @see HMC5883L_MODE_SINGLE + * @see HMC5883L_MODE_IDLE + * @see HMC5883L_RA_MODE + * @see HMC5883L_MODEREG_BIT + * @see HMC5883L_MODEREG_LENGTH + */ +void HMC5883L::setMode(uint8_t newMode) { + // use this method to guarantee that bits 7-2 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, newMode << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + mode = newMode; // track to tell if we have to clear bit 7 after a read +} + +// DATA* registers + +/** Get 3-axis heading measurements. + * In the event the ADC reading overflows or underflows for the given channel, + * or if there is a math overflow during the bias measurement, this data + * register will contain the value -4096. This register value will clear when + * after the next valid measurement is made. Note that this method automatically + * clears the appropriate bit in the MODE register if Single mode is active. + * @param x 16-bit signed integer container for X-axis heading + * @param y 16-bit signed integer container for Y-axis heading + * @param z 16-bit signed integer container for Z-axis heading + * @see HMC5883L_RA_DATAX_H + */ +void HMC5883L::getHeading(int16_t *x, int16_t *y, int16_t *z) { + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[4]) << 8) | buffer[5]; + *z = (((int16_t)buffer[2]) << 8) | buffer[3]; +} +/** Get X-axis heading measurement. + * @return 16-bit signed integer with X-axis heading + * @see HMC5883L_RA_DATAX_H + */ +int16_t HMC5883L::getHeadingX() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis heading measurement. + * @return 16-bit signed integer with Y-axis heading + * @see HMC5883L_RA_DATAY_H + */ +int16_t HMC5883L::getHeadingY() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get Z-axis heading measurement. + * @return 16-bit signed integer with Z-axis heading + * @see HMC5883L_RA_DATAZ_H + */ +int16_t HMC5883L::getHeadingZ() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[2]) << 8) | buffer[3]; +} + +// STATUS register + +/** Get data output register lock status. + * This bit is set when this some but not all for of the six data output + * registers have been read. When this bit is set, the six data output registers + * are locked and any new data will not be placed in these register until one of + * three conditions are met: one, all six bytes have been read or the mode + * changed, two, the mode is changed, or three, the measurement configuration is + * changed. + * @return Data output register lock status + * @see HMC5883L_RA_STATUS + * @see HMC5883L_STATUS_LOCK_BIT + */ +bool HMC5883L::getLockStatus() { + I2Cdev::readBit(devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_LOCK_BIT, buffer); + return buffer[0]; +} +/** Get data ready status. + * This bit is set when data is written to all six data registers, and cleared + * when the device initiates a write to the data output registers and after one + * or more of the data output registers are written to. When RDY bit is clear it + * shall remain cleared for 250 us. DRDY pin can be used as an alternative to + * the status register for monitoring the device for measurement data. + * @return Data ready status + * @see HMC5883L_RA_STATUS + * @see HMC5883L_STATUS_READY_BIT + */ +bool HMC5883L::getReadyStatus() { + I2Cdev::readBit(devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_READY_BIT, buffer); + return buffer[0]; +} + +// ID_* registers + +/** Get identification byte A + * @return ID_A byte (should be 01001000, ASCII value 'H') + */ +uint8_t HMC5883L::getIDA() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_A, buffer); + return buffer[0]; +} +/** Get identification byte B + * @return ID_A byte (should be 00110100, ASCII value '4') + */ +uint8_t HMC5883L::getIDB() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_B, buffer); + return buffer[0]; +} +/** Get identification byte C + * @return ID_A byte (should be 00110011, ASCII value '3') + */ +uint8_t HMC5883L::getIDC() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_C, buffer); + return buffer[0]; +} diff --git a/firmware/lib/imu/HMC5883L.h b/firmware/lib/imu/HMC5883L.h new file mode 100644 index 0000000..dcb1974 --- /dev/null +++ b/firmware/lib/imu/HMC5883L.h @@ -0,0 +1,148 @@ +// I2Cdev library collection - HMC5883L I2C device class header file +// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B) +// 6/12/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-12 - fixed swapped Y/Z axes +// 2011-08-22 - small Doxygen comment fixes +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#ifndef _HMC5883L_H_ +#define _HMC5883L_H_ + +#include "I2Cdev.h" + +#define HMC5883L_ADDRESS 0x1E // this device only has one address +#define HMC5883L_DEFAULT_ADDRESS 0x1E + +#define HMC5883L_RA_CONFIG_A 0x00 +#define HMC5883L_RA_CONFIG_B 0x01 +#define HMC5883L_RA_MODE 0x02 +#define HMC5883L_RA_DATAX_H 0x03 +#define HMC5883L_RA_DATAX_L 0x04 +#define HMC5883L_RA_DATAZ_H 0x05 +#define HMC5883L_RA_DATAZ_L 0x06 +#define HMC5883L_RA_DATAY_H 0x07 +#define HMC5883L_RA_DATAY_L 0x08 +#define HMC5883L_RA_STATUS 0x09 +#define HMC5883L_RA_ID_A 0x0A +#define HMC5883L_RA_ID_B 0x0B +#define HMC5883L_RA_ID_C 0x0C + +#define HMC5883L_CRA_AVERAGE_BIT 6 +#define HMC5883L_CRA_AVERAGE_LENGTH 2 +#define HMC5883L_CRA_RATE_BIT 4 +#define HMC5883L_CRA_RATE_LENGTH 3 +#define HMC5883L_CRA_BIAS_BIT 1 +#define HMC5883L_CRA_BIAS_LENGTH 2 + +#define HMC5883L_AVERAGING_1 0x00 +#define HMC5883L_AVERAGING_2 0x01 +#define HMC5883L_AVERAGING_4 0x02 +#define HMC5883L_AVERAGING_8 0x03 + +#define HMC5883L_RATE_0P75 0x00 +#define HMC5883L_RATE_1P5 0x01 +#define HMC5883L_RATE_3 0x02 +#define HMC5883L_RATE_7P5 0x03 +#define HMC5883L_RATE_15 0x04 +#define HMC5883L_RATE_30 0x05 +#define HMC5883L_RATE_75 0x06 + +#define HMC5883L_BIAS_NORMAL 0x00 +#define HMC5883L_BIAS_POSITIVE 0x01 +#define HMC5883L_BIAS_NEGATIVE 0x02 + +#define HMC5883L_CRB_GAIN_BIT 7 +#define HMC5883L_CRB_GAIN_LENGTH 3 + +#define HMC5883L_GAIN_1370 0x00 +#define HMC5883L_GAIN_1090 0x01 +#define HMC5883L_GAIN_820 0x02 +#define HMC5883L_GAIN_660 0x03 +#define HMC5883L_GAIN_440 0x04 +#define HMC5883L_GAIN_390 0x05 +#define HMC5883L_GAIN_330 0x06 +#define HMC5883L_GAIN_220 0x07 + +#define HMC5883L_MODEREG_BIT 1 +#define HMC5883L_MODEREG_LENGTH 2 + +#define HMC5883L_MODE_CONTINUOUS 0x00 +#define HMC5883L_MODE_SINGLE 0x01 +#define HMC5883L_MODE_IDLE 0x02 + +#define HMC5883L_STATUS_LOCK_BIT 1 +#define HMC5883L_STATUS_READY_BIT 0 + +class HMC5883L { + public: + HMC5883L(); + HMC5883L(uint8_t address); + + void initialize(); + bool testConnection(); + + // CONFIG_A register + uint8_t getSampleAveraging(); + void setSampleAveraging(uint8_t averaging); + uint8_t getDataRate(); + void setDataRate(uint8_t rate); + uint8_t getMeasurementBias(); + void setMeasurementBias(uint8_t bias); + + // CONFIG_B register + uint8_t getGain(); + void setGain(uint8_t gain); + + // MODE register + uint8_t getMode(); + void setMode(uint8_t mode); + + // DATA* registers + void getHeading(int16_t *x, int16_t *y, int16_t *z); + int16_t getHeadingX(); + int16_t getHeadingY(); + int16_t getHeadingZ(); + + // STATUS register + bool getLockStatus(); + bool getReadyStatus(); + + // ID_* registers + uint8_t getIDA(); + uint8_t getIDB(); + uint8_t getIDC(); + + private: + uint8_t devAddr; + uint8_t buffer[6]; + uint8_t mode; +}; + +#endif /* _HMC5883L_H_ */ diff --git a/firmware/lib/imu/I2Cdev.cpp b/firmware/lib/imu/I2Cdev.cpp new file mode 100644 index 0000000..f56d139 --- /dev/null +++ b/firmware/lib/imu/I2Cdev.cpp @@ -0,0 +1,1461 @@ +// I2Cdev library collection - Main I2C device class +// Abstracts bit and byte I2C R/W functions into a convenient class +// 2013-06-05 by Jeff Rowberg +// +// Changelog: +// 2013-05-06 - add Francesco Ferrara's Fastwire v0.24 implementation with small modifications +// 2013-05-05 - fix issue with writing bit values to words (Sasquatch/Farzanegan) +// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire +// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation +// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums) +// 2011-10-03 - added automatic Arduino version detection for ease of use +// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications +// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x) +// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default +// 2011-08-02 - added support for 16-bit registers +// - fixed incorrect Doxygen comments on some methods +// - added timeout value for read operations (thanks mem @ Arduino forums) +// 2011-07-30 - changed read/write function structures to return success or byte counts +// - made all methods static for multi-device memory savings +// 2011-07-28 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "I2Cdev.h" +//#include // Add this line + +#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + + #ifdef I2CDEV_IMPLEMENTATION_WARNINGS + #if ARDUINO < 100 + #warning Using outdated Arduino IDE with Wire library is functionally limiting. + #warning Arduino IDE v1.6.5+ with I2Cdev Fastwire implementation is recommended. + #warning This I2Cdev implementation does not support: + #warning - Repeated starts conditions + #warning - Timeout detection (some Wire requests block forever) + #elif ARDUINO == 100 + #warning Using outdated Arduino IDE with Wire library is functionally limiting. + #warning Arduino IDE v1.6.5+ with I2Cdev Fastwire implementation is recommended. + #warning This I2Cdev implementation does not support: + #warning - Repeated starts conditions + #warning - Timeout detection (some Wire requests block forever) + #elif ARDUINO > 100 + /*#warning Using current Arduino IDE with Wire library is functionally limiting. + #warning Arduino IDE v1.6.5+ with I2CDEV_BUILTIN_FASTWIRE implementation is recommended. + #warning This I2Cdev implementation does not support: + #warning - Timeout detection (some Wire requests block forever)*/ + #endif + #endif + +#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + + //#error The I2CDEV_BUILTIN_FASTWIRE implementation is known to be broken right now. Patience, Iago! + +#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE + + #ifdef I2CDEV_IMPLEMENTATION_WARNINGS + #warning Using I2CDEV_BUILTIN_NBWIRE implementation may adversely affect interrupt detection. + #warning This I2Cdev implementation does not support: + #warning - Repeated starts conditions + #endif + + // NBWire implementation based heavily on code by Gene Knight + // Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html + // Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html + TwoWire Wire; + +#endif + +#define BUFFER_LENGTH 16 // added 07.07.2023 + +/** Default constructor. + */ +I2Cdev::I2Cdev() { +} + +/** Read a single bit from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitNum Bit position to read (0-7) + * @param data Container for single bit value + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout) { + uint8_t b; + uint8_t count = readByte(devAddr, regAddr, &b, timeout); + *data = b & (1 << bitNum); + return count; +} + +/** Read a single bit from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitNum Bit position to read (0-15) + * @param data Container for single bit value + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout) { + uint16_t b; + uint8_t count = readWord(devAddr, regAddr, &b, timeout); + *data = b & (1 << bitNum); + return count; +} + +/** Read multiple bits from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitStart First bit position to read (0-7) + * @param length Number of bits to read (not more than 8) + * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout) { + // 01101001 read byte + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 010 masked + // -> 010 shifted + uint8_t count, b; + if ((count = readByte(devAddr, regAddr, &b, timeout)) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + b &= mask; + b >>= (bitStart - length + 1); + *data = b; + } + return count; +} + +/** Read multiple bits from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitStart First bit position to read (0-15) + * @param length Number of bits to read (not more than 16) + * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (1 = success, 0 = failure, -1 = timeout) + */ +int8_t I2Cdev::readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout) { + // 1101011001101001 read byte + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 010 masked + // -> 010 shifted + uint8_t count; + uint16_t w; + if ((count = readWord(devAddr, regAddr, &w, timeout)) != 0) { + uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1); + w &= mask; + w >>= (bitStart - length + 1); + *data = w; + } + return count; +} + +/** Read single byte from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param data Container for byte value read from device + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout) { + return readBytes(devAddr, regAddr, 1, data, timeout); +} + +/** Read single word from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param data Container for word value read from device + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout) { + return readWords(devAddr, regAddr, 1, data, timeout); +} + +/** Read multiple bytes from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of bytes to read + * @param data Buffer to store read data in + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Number of bytes read (-1 indicates failure) + */ +int8_t I2Cdev::readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") reading "); + Serial.print(length, DEC); + Serial.print(" bytes from 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); + #endif + + int8_t count = 0; + uint32_t t1 = millis(); + + // #if (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE) //|| (I2CDEV_IMPLEMENTATION == I2CDEV_ESP32_WIRE) + + // #if (ARDUINO < 100) + // // Arduino v00xx (before v1.0), Wire library + + // // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // // smaller chunks instead of all at once + // for (uint8_t k = 0; k < length; k += min(length, BUFFER_LENGTH)) { + // Wire.beginTransmission(devAddr); + // Wire.send(regAddr); + // Wire.endTransmission(); + // Wire.beginTransmission(devAddr); + // Wire.requestFrom(devAddr, (uint8_t)min(length - k, BUFFER_LENGTH)); + + // for (; Wire.available() && (timeout == 0 || millis() - t1 < timeout); count++) { + // data[count] = Wire.receive(); + // #ifdef I2CDEV_SERIAL_DEBUG + // Serial.print(data[count], HEX); + // if (count + 1 < length) Serial.print(" "); + // #endif + // } + + // Wire.endTransmission(); + // } + // #elif (ARDUINO == 100) + // // Arduino v1.0.0, Wire library + // // Adds standardized write() and read() stream methods instead of send() and receive() + + // // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // // smaller chunks instead of all at once + // for (uint8_t k = 0; k < length; k += min(length, BUFFER_LENGTH)) { + // Wire.beginTransmission(devAddr); + // Wire.write(regAddr); + // Wire.endTransmission(); + // Wire.beginTransmission(devAddr); + // Wire.requestFrom(devAddr, (uint8_t)min(length - k, BUFFER_LENGTH)); + + // for (; Wire.available() && (timeout == 0 || millis() - t1 < timeout); count++) { + // data[count] = Wire.read(); + // #ifdef I2CDEV_SERIAL_DEBUG + // Serial.print(data[count], HEX); + // if (count + 1 < length) Serial.print(" "); + // #endif + // } + + // Wire.endTransmission(); + // } + // #elif (ARDUINO > 100) + // // Arduino v1.0.1+, Wire library + // // Adds official support for repeated start condition, yay! + + // // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // // smaller chunks instead of all at once + // for (uint8_t k = 0; k < length; k += min(length, BUFFER_LENGTH)) { + // //for (uint8_t k = 0; k < length; k += std::min(length, static_cast(BUFFER_LENGTH))) { // changed 07.07.2023 + // Wire.beginTransmission(devAddr); + // Wire.write(regAddr); + // Wire.endTransmission(); + // Wire.beginTransmission(devAddr); + // Wire.requestFrom(devAddr, (uint8_t)min(length - k, BUFFER_LENGTH)); + + // for (; Wire.available() && (timeout == 0 || millis() - t1 < timeout); count++) { + // data[count] = Wire.read(); + // #ifdef I2CDEV_SERIAL_DEBUG + // Serial.print(data[count], HEX); + // if (count + 1 < length) Serial.print(" "); + // #endif + // } + // } + // #endif + + // #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + + // // Fastwire library + // // no loop required for fastwire + // uint8_t status = Fastwire::readBuf(devAddr << 1, regAddr, data, length); + // if (status == 0) { + // count = length; // success + // } else { + // count = -1; // error + // } + + // #endif + + // check for timeout + if (timeout > 0 && millis() - t1 >= timeout && count < length) count = -1; // timeout + + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(". Done ("); + Serial.print(count, DEC); + Serial.println(" read)."); + #endif + + return count; +} + +/** Read multiple words from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of words to read + * @param data Buffer to store read data in + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Number of words read (-1 indicates failure) + */ +int8_t I2Cdev::readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") reading "); + Serial.print(length, DEC); + Serial.print(" words from 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); + #endif + + int8_t count = 0; + uint32_t t1 = millis(); + + #if (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE) + + #if (ARDUINO < 100) + // Arduino v00xx (before v1.0), Wire library + + // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // smaller chunks instead of all at once + for (uint8_t k = 0; k < length * 2; k += min(length * 2, BUFFER_LENGTH)) { + Wire.beginTransmission(devAddr); + Wire.send(regAddr); + Wire.endTransmission(); + Wire.beginTransmission(devAddr); + Wire.requestFrom(devAddr, (uint8_t)(length * 2)); // length=words, this wants bytes + + bool msb = true; // starts with MSB, then LSB + for (; Wire.available() && count < length && (timeout == 0 || millis() - t1 < timeout);) { + if (msb) { + // first byte is bits 15-8 (MSb=15) + data[count] = Wire.receive() << 8; + } else { + // second byte is bits 7-0 (LSb=0) + data[count] |= Wire.receive(); + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count + 1 < length) Serial.print(" "); + #endif + count++; + } + msb = !msb; + } + + Wire.endTransmission(); + } + #elif (ARDUINO == 100) + // Arduino v1.0.0, Wire library + // Adds standardized write() and read() stream methods instead of send() and receive() + + // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // smaller chunks instead of all at once + for (uint8_t k = 0; k < length * 2; k += min(length * 2, BUFFER_LENGTH)) { + Wire.beginTransmission(devAddr); + Wire.write(regAddr); + Wire.endTransmission(); + Wire.beginTransmission(devAddr); + Wire.requestFrom(devAddr, (uint8_t)(length * 2)); // length=words, this wants bytes + + bool msb = true; // starts with MSB, then LSB + for (; Wire.available() && count < length && (timeout == 0 || millis() - t1 < timeout);) { + if (msb) { + // first byte is bits 15-8 (MSb=15) + data[count] = Wire.read() << 8; + } else { + // second byte is bits 7-0 (LSb=0) + data[count] |= Wire.read(); + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count + 1 < length) Serial.print(" "); + #endif + count++; + } + msb = !msb; + } + + Wire.endTransmission(); + } + #elif (ARDUINO > 100) + // Arduino v1.0.1+, Wire library + // Adds official support for repeated start condition, yay! + + // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // smaller chunks instead of all at once + for (uint8_t k = 0; k < length * 2; k += min(length * 2, BUFFER_LENGTH)) { + Wire.beginTransmission(devAddr); + Wire.write(regAddr); + Wire.endTransmission(); + Wire.beginTransmission(devAddr); + Wire.requestFrom(devAddr, (uint8_t)(length * 2)); // length=words, this wants bytes + + bool msb = true; // starts with MSB, then LSB + for (; Wire.available() && count < length && (timeout == 0 || millis() - t1 < timeout);) { + if (msb) { + // first byte is bits 15-8 (MSb=15) + data[count] = Wire.read() << 8; + } else { + // second byte is bits 7-0 (LSb=0) + data[count] |= Wire.read(); + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count + 1 < length) Serial.print(" "); + #endif + count++; + } + msb = !msb; + } + + Wire.endTransmission(); + } + #endif + + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + + // Fastwire library + // no loop required for fastwire + uint16_t intermediate[(uint8_t)length]; + uint8_t status = Fastwire::readBuf(devAddr << 1, regAddr, (uint8_t *)intermediate, (uint8_t)(length * 2)); + if (status == 0) { + count = length; // success + for (uint8_t i = 0; i < length; i++) { + data[i] = (intermediate[2*i] << 8) | intermediate[2*i + 1]; + } + } else { + count = -1; // error + } + + #endif + + if (timeout > 0 && millis() - t1 >= timeout && count < length) count = -1; // timeout + + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(". Done ("); + Serial.print(count, DEC); + Serial.println(" read)."); + #endif + + return count; +} + +/** write a single bit in an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitNum Bit position to write (0-7) + * @param value New bit value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) { + uint8_t b; + readByte(devAddr, regAddr, &b); + b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); + return writeByte(devAddr, regAddr, b); +} + +/** write a single bit in a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitNum Bit position to write (0-15) + * @param value New bit value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data) { + uint16_t w; + readWord(devAddr, regAddr, &w); + w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum)); + return writeWord(devAddr, regAddr, w); +} + +/** Write multiple bits in an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitStart First bit position to write (0-7) + * @param length Number of bits to write (not more than 8) + * @param data Right-aligned value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) { + // 010 value to write + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 00011100 mask byte + // 10101111 original value (sample) + // 10100011 original & ~mask + // 10101011 masked | value + uint8_t b; + if (readByte(devAddr, regAddr, &b) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + data <<= (bitStart - length + 1); // shift data into correct position + data &= mask; // zero all non-important bits in data + b &= ~(mask); // zero all important bits in existing byte + b |= data; // combine data with existing byte + return writeByte(devAddr, regAddr, b); + } else { + return false; + } +} + +/** Write multiple bits in a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitStart First bit position to write (0-15) + * @param length Number of bits to write (not more than 16) + * @param data Right-aligned value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data) { + // 010 value to write + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 0001110000000000 mask word + // 1010111110010110 original value (sample) + // 1010001110010110 original & ~mask + // 1010101110010110 masked | value + uint16_t w; + if (readWord(devAddr, regAddr, &w) != 0) { + uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1); + data <<= (bitStart - length + 1); // shift data into correct position + data &= mask; // zero all non-important bits in data + w &= ~(mask); // zero all important bits in existing word + w |= data; // combine data with existing word + return writeWord(devAddr, regAddr, w); + } else { + return false; + } +} + +/** Write single byte to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register address to write to + * @param data New byte value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) { + return writeBytes(devAddr, regAddr, 1, &data); +} + +/** Write single word to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register address to write to + * @param data New word value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) { + return writeWords(devAddr, regAddr, 1, &data); +} + +/** Write multiple bytes to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of bytes to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") writing "); + Serial.print(length, DEC); + Serial.print(" bytes to 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); + #endif + uint8_t status = 0; + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.beginTransmission(devAddr); + Wire.send((uint8_t) regAddr); // send address + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + Wire.beginTransmission(devAddr); + Wire.write((uint8_t) regAddr); // send address + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::beginTransmission(devAddr); + Fastwire::write(regAddr); + #endif + for (uint8_t i = 0; i < length; i++) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[i], HEX); + if (i + 1 < length) Serial.print(" "); + #endif + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.send((uint8_t) data[i]); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + Wire.write((uint8_t) data[i]); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::write((uint8_t) data[i]); + #endif + } + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.endTransmission(); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + status = Wire.endTransmission(); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::stop(); + //status = Fastwire::endTransmission(); + #endif + #ifdef I2CDEV_SERIAL_DEBUG + Serial.println(". Done."); + #endif + return status == 0; +} + +/** Write multiple words to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of words to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev::writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") writing "); + Serial.print(length, DEC); + Serial.print(" words to 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); + #endif + uint8_t status = 0; + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.beginTransmission(devAddr); + Wire.send(regAddr); // send address + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + Wire.beginTransmission(devAddr); + Wire.write(regAddr); // send address + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::beginTransmission(devAddr); + Fastwire::write(regAddr); + #endif + for (uint8_t i = 0; i < length * 2; i++) { + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[i], HEX); + if (i + 1 < length) Serial.print(" "); + #endif + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.send((uint8_t)(data[i] >> 8)); // send MSB + Wire.send((uint8_t)data[i++]); // send LSB + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + Wire.write((uint8_t)(data[i] >> 8)); // send MSB + Wire.write((uint8_t)data[i++]); // send LSB + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::write((uint8_t)(data[i] >> 8)); // send MSB + status = Fastwire::write((uint8_t)data[i++]); // send LSB + if (status != 0) break; + #endif + } + #if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + Wire.endTransmission(); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + status = Wire.endTransmission(); + #elif (I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE) + Fastwire::stop(); + //status = Fastwire::endTransmission(); + #endif + #ifdef I2CDEV_SERIAL_DEBUG + Serial.println(". Done."); + #endif + return status == 0; +} + +/** Default timeout value for read operations. + * Set this to 0 to disable timeout detection. + */ +uint16_t I2Cdev::readTimeout = I2CDEV_DEFAULT_READ_TIMEOUT; + +#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + // I2C library + ////////////////////// + // Copyright(C) 2012 + // Francesco Ferrara + // ferrara[at]libero[point]it + ////////////////////// + + /* + FastWire + - 0.24 added stop + - 0.23 added reset + + This is a library to help faster programs to read I2C devices. + Copyright(C) 2012 Francesco Ferrara + occhiobello at gmail dot com + [used by Jeff Rowberg for I2Cdevlib with permission] + */ + + boolean Fastwire::waitInt() { + int l = 250; + while (!(TWCR & (1 << TWINT)) && l-- > 0); + return l > 0; + } + + void Fastwire::setup(int khz, boolean pullup) { + TWCR = 0; + #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega8__) || defined(__AVR_ATmega328P__) + // activate internal pull-ups for twi (PORTC bits 4 & 5) + // as per note from atmega8 manual pg167 + if (pullup) PORTC |= ((1 << 4) | (1 << 5)); + else PORTC &= ~((1 << 4) | (1 << 5)); + #elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__) + // activate internal pull-ups for twi (PORTC bits 0 & 1) + if (pullup) PORTC |= ((1 << 0) | (1 << 1)); + else PORTC &= ~((1 << 0) | (1 << 1)); + #else + // activate internal pull-ups for twi (PORTD bits 0 & 1) + // as per note from atmega128 manual pg204 + if (pullup) PORTD |= ((1 << 0) | (1 << 1)); + else PORTD &= ~((1 << 0) | (1 << 1)); + #endif + + TWSR = 0; // no prescaler => prescaler = 1 + TWBR = ((16000L / khz) - 16) / 2; // change the I2C clock rate + TWCR = 1 << TWEN; // enable twi module, no interrupt + } + + // added by Jeff Rowberg 2013-05-07: + // Arduino Wire-style "beginTransmission" function + // (takes 7-bit device address like the Wire method, NOT 8-bit: 0x68, not 0xD0/0xD1) + byte Fastwire::beginTransmission(byte device) { + byte twst, retry; + retry = 2; + do { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO) | (1 << TWSTA); + if (!waitInt()) return 1; + twst = TWSR & 0xF8; + if (twst != TW_START && twst != TW_REP_START) return 2; + + //Serial.print(device, HEX); + //Serial.print(" "); + TWDR = device << 1; // send device address without read bit (1) + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 3; + twst = TWSR & 0xF8; + } while (twst == TW_MT_SLA_NACK && retry-- > 0); + if (twst != TW_MT_SLA_ACK) return 4; + return 0; + } + + byte Fastwire::writeBuf(byte device, byte address, byte *data, byte num) { + byte twst, retry; + + retry = 2; + do { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO) | (1 << TWSTA); + if (!waitInt()) return 1; + twst = TWSR & 0xF8; + if (twst != TW_START && twst != TW_REP_START) return 2; + + //Serial.print(device, HEX); + //Serial.print(" "); + TWDR = device & 0xFE; // send device address without read bit (1) + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 3; + twst = TWSR & 0xF8; + } while (twst == TW_MT_SLA_NACK && retry-- > 0); + if (twst != TW_MT_SLA_ACK) return 4; + + //Serial.print(address, HEX); + //Serial.print(" "); + TWDR = address; // send data to the previously addressed device + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 5; + twst = TWSR & 0xF8; + if (twst != TW_MT_DATA_ACK) return 6; + + for (byte i = 0; i < num; i++) { + //Serial.print(data[i], HEX); + //Serial.print(" "); + TWDR = data[i]; // send data to the previously addressed device + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 7; + twst = TWSR & 0xF8; + if (twst != TW_MT_DATA_ACK) return 8; + } + //Serial.print("\n"); + + return 0; + } + + byte Fastwire::write(byte value) { + byte twst; + //Serial.println(value, HEX); + TWDR = value; // send data + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 1; + twst = TWSR & 0xF8; + if (twst != TW_MT_DATA_ACK) return 2; + return 0; + } + + byte Fastwire::readBuf(byte device, byte address, byte *data, byte num) { + byte twst, retry; + + retry = 2; + do { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO) | (1 << TWSTA); + if (!waitInt()) return 16; + twst = TWSR & 0xF8; + if (twst != TW_START && twst != TW_REP_START) return 17; + + //Serial.print(device, HEX); + //Serial.print(" "); + TWDR = device & 0xfe; // send device address to write + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 18; + twst = TWSR & 0xF8; + } while (twst == TW_MT_SLA_NACK && retry-- > 0); + if (twst != TW_MT_SLA_ACK) return 19; + + //Serial.print(address, HEX); + //Serial.print(" "); + TWDR = address; // send data to the previously addressed device + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 20; + twst = TWSR & 0xF8; + if (twst != TW_MT_DATA_ACK) return 21; + + /***/ + + retry = 2; + do { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO) | (1 << TWSTA); + if (!waitInt()) return 22; + twst = TWSR & 0xF8; + if (twst != TW_START && twst != TW_REP_START) return 23; + + //Serial.print(device, HEX); + //Serial.print(" "); + TWDR = device | 0x01; // send device address with the read bit (1) + TWCR = (1 << TWINT) | (1 << TWEN); + if (!waitInt()) return 24; + twst = TWSR & 0xF8; + } while (twst == TW_MR_SLA_NACK && retry-- > 0); + if (twst != TW_MR_SLA_ACK) return 25; + + for (uint8_t i = 0; i < num; i++) { + if (i == num - 1) + TWCR = (1 << TWINT) | (1 << TWEN); + else + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWEA); + if (!waitInt()) return 26; + twst = TWSR & 0xF8; + if (twst != TW_MR_DATA_ACK && twst != TW_MR_DATA_NACK) return twst; + data[i] = TWDR; + //Serial.print(data[i], HEX); + //Serial.print(" "); + } + //Serial.print("\n"); + stop(); + + return 0; + } + + void Fastwire::reset() { + TWCR = 0; + } + + byte Fastwire::stop() { + TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO); + if (!waitInt()) return 1; + return 0; + } +#endif + +#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE + // NBWire implementation based heavily on code by Gene Knight + // Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html + // Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html + + /* + call this version 1.0 + + Offhand, the only funky part that I can think of is in nbrequestFrom, where the buffer + length and index are set *before* the data is actually read. The problem is that these + are variables local to the TwoWire object, and by the time we actually have read the + data, and know what the length actually is, we have no simple access to the object's + variables. The actual bytes read *is* given to the callback function, though. + + The ISR code for a slave receiver is commented out. I don't have that setup, and can't + verify it at this time. Save it for 2.0! + + The handling of the read and write processes here is much like in the demo sketch code: + the process is broken down into sequential functions, where each registers the next as a + callback, essentially. + + For example, for the Read process, twi_read00 just returns if TWI is not yet in a + ready state. When there's another interrupt, and the interface *is* ready, then it + sets up the read, starts it, and registers twi_read01 as the function to call after + the *next* interrupt. twi_read01, then, just returns if the interface is still in a + "reading" state. When the reading is done, it copies the information to the buffer, + cleans up, and calls the user-requested callback function with the actual number of + bytes read. + + The writing is similar. + + Questions, comments and problems can go to Gene@Telobot.com. + + Thumbs Up! + Gene Knight + + */ + + uint8_t TwoWire::rxBuffer[NBWIRE_BUFFER_LENGTH]; + uint8_t TwoWire::rxBufferIndex = 0; + uint8_t TwoWire::rxBufferLength = 0; + + uint8_t TwoWire::txAddress = 0; + uint8_t TwoWire::txBuffer[NBWIRE_BUFFER_LENGTH]; + uint8_t TwoWire::txBufferIndex = 0; + uint8_t TwoWire::txBufferLength = 0; + + //uint8_t TwoWire::transmitting = 0; + void (*TwoWire::user_onRequest)(void); + void (*TwoWire::user_onReceive)(int); + + static volatile uint8_t twi_transmitting; + static volatile uint8_t twi_state; + static uint8_t twi_slarw; + static volatile uint8_t twi_error; + static uint8_t twi_masterBuffer[TWI_BUFFER_LENGTH]; + static volatile uint8_t twi_masterBufferIndex; + static uint8_t twi_masterBufferLength; + static uint8_t twi_rxBuffer[TWI_BUFFER_LENGTH]; + static volatile uint8_t twi_rxBufferIndex; + //static volatile uint8_t twi_Interrupt_Continue_Command; + static volatile uint8_t twi_Return_Value; + static volatile uint8_t twi_Done; + void (*twi_cbendTransmissionDone)(int); + void (*twi_cbreadFromDone)(int); + + void twi_init() { + // initialize state + twi_state = TWI_READY; + + // activate internal pull-ups for twi + // as per note from atmega8 manual pg167 + sbi(PORTC, 4); + sbi(PORTC, 5); + + // initialize twi prescaler and bit rate + cbi(TWSR, TWPS0); // TWI Status Register - Prescaler bits + cbi(TWSR, TWPS1); + + /* twi bit rate formula from atmega128 manual pg 204 + SCL Frequency = CPU Clock Frequency / (16 + (2 * TWBR)) + note: TWBR should be 10 or higher for master mode + It is 72 for a 16mhz Wiring board with 100kHz TWI */ + + TWBR = ((CPU_FREQ / TWI_FREQ) - 16) / 2; // bitrate register + // enable twi module, acks, and twi interrupt + + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA); + + /* TWEN - TWI Enable Bit + TWIE - TWI Interrupt Enable + TWEA - TWI Enable Acknowledge Bit + TWINT - TWI Interrupt Flag + TWSTA - TWI Start Condition + */ + } + + typedef struct { + uint8_t address; + uint8_t* data; + uint8_t length; + uint8_t wait; + uint8_t i; + } twi_Write_Vars; + + twi_Write_Vars *ptwv = 0; + static void (*fNextInterruptFunction)(void) = 0; + + void twi_Finish(byte bRetVal) { + if (ptwv) { + free(ptwv); + ptwv = 0; + } + twi_Done = 0xFF; + twi_Return_Value = bRetVal; + fNextInterruptFunction = 0; + } + + uint8_t twii_WaitForDone(uint16_t timeout) { + uint32_t endMillis = millis() + timeout; + while (!twi_Done && (timeout == 0 || millis() < endMillis)) continue; + return twi_Return_Value; + } + + void twii_SetState(uint8_t ucState) { + twi_state = ucState; + } + + void twii_SetError(uint8_t ucError) { + twi_error = ucError ; + } + + void twii_InitBuffer(uint8_t ucPos, uint8_t ucLength) { + twi_masterBufferIndex = 0; + twi_masterBufferLength = ucLength; + } + + void twii_CopyToBuf(uint8_t* pData, uint8_t ucLength) { + uint8_t i; + for (i = 0; i < ucLength; ++i) { + twi_masterBuffer[i] = pData[i]; + } + } + + void twii_CopyFromBuf(uint8_t *pData, uint8_t ucLength) { + uint8_t i; + for (i = 0; i < ucLength; ++i) { + pData[i] = twi_masterBuffer[i]; + } + } + + void twii_SetSlaRW(uint8_t ucSlaRW) { + twi_slarw = ucSlaRW; + } + + void twii_SetStart() { + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT) | _BV(TWSTA); + } + + void twi_write01() { + if (TWI_MTX == twi_state) return; // blocking test + twi_transmitting = 0 ; + if (twi_error == 0xFF) + twi_Finish (0); // success + else if (twi_error == TW_MT_SLA_NACK) + twi_Finish (2); // error: address send, nack received + else if (twi_error == TW_MT_DATA_NACK) + twi_Finish (3); // error: data send, nack received + else + twi_Finish (4); // other twi error + if (twi_cbendTransmissionDone) return twi_cbendTransmissionDone(twi_Return_Value); + return; + } + + + void twi_write00() { + if (TWI_READY != twi_state) return; // blocking test + if (TWI_BUFFER_LENGTH < ptwv -> length) { + twi_Finish(1); // end write with error 1 + return; + } + twi_Done = 0x00; // show as working + twii_SetState(TWI_MTX); // to transmitting + twii_SetError(0xFF); // to No Error + twii_InitBuffer(0, ptwv -> length); // pointer and length + twii_CopyToBuf(ptwv -> data, ptwv -> length); // get the data + twii_SetSlaRW((ptwv -> address << 1) | TW_WRITE); // write command + twii_SetStart(); // start the cycle + fNextInterruptFunction = twi_write01; // next routine + return twi_write01(); + } + + void twi_writeTo(uint8_t address, uint8_t* data, uint8_t length, uint8_t wait) { + uint8_t i; + ptwv = (twi_Write_Vars *)malloc(sizeof(twi_Write_Vars)); + ptwv -> address = address; + ptwv -> data = data; + ptwv -> length = length; + ptwv -> wait = wait; + fNextInterruptFunction = twi_write00; + return twi_write00(); + } + + void twi_read01() { + if (TWI_MRX == twi_state) return; // blocking test + if (twi_masterBufferIndex < ptwv -> length) ptwv -> length = twi_masterBufferIndex; + twii_CopyFromBuf(ptwv -> data, ptwv -> length); + twi_Finish(ptwv -> length); + if (twi_cbreadFromDone) return twi_cbreadFromDone(twi_Return_Value); + return; + } + + void twi_read00() { + if (TWI_READY != twi_state) return; // blocking test + if (TWI_BUFFER_LENGTH < ptwv -> length) twi_Finish(0); // error return + twi_Done = 0x00; // show as working + twii_SetState(TWI_MRX); // reading + twii_SetError(0xFF); // reset error + twii_InitBuffer(0, ptwv -> length - 1); // init to one less than length + twii_SetSlaRW((ptwv -> address << 1) | TW_READ); // read command + twii_SetStart(); // start cycle + fNextInterruptFunction = twi_read01; + return twi_read01(); + } + + void twi_readFrom(uint8_t address, uint8_t* data, uint8_t length) { + uint8_t i; + + ptwv = (twi_Write_Vars *)malloc(sizeof(twi_Write_Vars)); + ptwv -> address = address; + ptwv -> data = data; + ptwv -> length = length; + fNextInterruptFunction = twi_read00; + return twi_read00(); + } + + void twi_reply(uint8_t ack) { + // transmit master read ready signal, with or without ack + if (ack){ + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWINT) | _BV(TWEA); + } else { + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWINT); + } + } + + void twi_stop(void) { + // send stop condition + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT) | _BV(TWSTO); + + // wait for stop condition to be exectued on bus + // TWINT is not set after a stop condition! + while (TWCR & _BV(TWSTO)) { + continue; + } + + // update twi state + twi_state = TWI_READY; + } + + void twi_releaseBus(void) { + // release bus + TWCR = _BV(TWEN) | _BV(TWIE) | _BV(TWEA) | _BV(TWINT); + + // update twi state + twi_state = TWI_READY; + } + + SIGNAL(TWI_vect) { + switch (TW_STATUS) { + // All Master + case TW_START: // sent start condition + case TW_REP_START: // sent repeated start condition + // copy device address and r/w bit to output register and ack + TWDR = twi_slarw; + twi_reply(1); + break; + + // Master Transmitter + case TW_MT_SLA_ACK: // slave receiver acked address + case TW_MT_DATA_ACK: // slave receiver acked data + // if there is data to send, send it, otherwise stop + if (twi_masterBufferIndex < twi_masterBufferLength) { + // copy data to output register and ack + TWDR = twi_masterBuffer[twi_masterBufferIndex++]; + twi_reply(1); + } else { + twi_stop(); + } + break; + + case TW_MT_SLA_NACK: // address sent, nack received + twi_error = TW_MT_SLA_NACK; + twi_stop(); + break; + + case TW_MT_DATA_NACK: // data sent, nack received + twi_error = TW_MT_DATA_NACK; + twi_stop(); + break; + + case TW_MT_ARB_LOST: // lost bus arbitration + twi_error = TW_MT_ARB_LOST; + twi_releaseBus(); + break; + + // Master Receiver + case TW_MR_DATA_ACK: // data received, ack sent + // put byte into buffer + twi_masterBuffer[twi_masterBufferIndex++] = TWDR; + + case TW_MR_SLA_ACK: // address sent, ack received + // ack if more bytes are expected, otherwise nack + if (twi_masterBufferIndex < twi_masterBufferLength) { + twi_reply(1); + } else { + twi_reply(0); + } + break; + + case TW_MR_DATA_NACK: // data received, nack sent + // put final byte into buffer + twi_masterBuffer[twi_masterBufferIndex++] = TWDR; + + case TW_MR_SLA_NACK: // address sent, nack received + twi_stop(); + break; + + // TW_MR_ARB_LOST handled by TW_MT_ARB_LOST case + + // Slave Receiver (NOT IMPLEMENTED YET) + /* + case TW_SR_SLA_ACK: // addressed, returned ack + case TW_SR_GCALL_ACK: // addressed generally, returned ack + case TW_SR_ARB_LOST_SLA_ACK: // lost arbitration, returned ack + case TW_SR_ARB_LOST_GCALL_ACK: // lost arbitration, returned ack + // enter slave receiver mode + twi_state = TWI_SRX; + + // indicate that rx buffer can be overwritten and ack + twi_rxBufferIndex = 0; + twi_reply(1); + break; + + case TW_SR_DATA_ACK: // data received, returned ack + case TW_SR_GCALL_DATA_ACK: // data received generally, returned ack + // if there is still room in the rx buffer + if (twi_rxBufferIndex < TWI_BUFFER_LENGTH) { + // put byte in buffer and ack + twi_rxBuffer[twi_rxBufferIndex++] = TWDR; + twi_reply(1); + } else { + // otherwise nack + twi_reply(0); + } + break; + + case TW_SR_STOP: // stop or repeated start condition received + // put a null char after data if there's room + if (twi_rxBufferIndex < TWI_BUFFER_LENGTH) { + twi_rxBuffer[twi_rxBufferIndex] = 0; + } + + // sends ack and stops interface for clock stretching + twi_stop(); + + // callback to user defined callback + twi_onSlaveReceive(twi_rxBuffer, twi_rxBufferIndex); + + // since we submit rx buffer to "wire" library, we can reset it + twi_rxBufferIndex = 0; + + // ack future responses and leave slave receiver state + twi_releaseBus(); + break; + + case TW_SR_DATA_NACK: // data received, returned nack + case TW_SR_GCALL_DATA_NACK: // data received generally, returned nack + // nack back at master + twi_reply(0); + break; + + // Slave Transmitter + case TW_ST_SLA_ACK: // addressed, returned ack + case TW_ST_ARB_LOST_SLA_ACK: // arbitration lost, returned ack + // enter slave transmitter mode + twi_state = TWI_STX; + + // ready the tx buffer index for iteration + twi_txBufferIndex = 0; + + // set tx buffer length to be zero, to verify if user changes it + twi_txBufferLength = 0; + + // request for txBuffer to be filled and length to be set + // note: user must call twi_transmit(bytes, length) to do this + twi_onSlaveTransmit(); + + // if they didn't change buffer & length, initialize it + if (0 == twi_txBufferLength) { + twi_txBufferLength = 1; + twi_txBuffer[0] = 0x00; + } + + // transmit first byte from buffer, fall through + + case TW_ST_DATA_ACK: // byte sent, ack returned + // copy data to output register + TWDR = twi_txBuffer[twi_txBufferIndex++]; + + // if there is more to send, ack, otherwise nack + if (twi_txBufferIndex < twi_txBufferLength) { + twi_reply(1); + } else { + twi_reply(0); + } + break; + + case TW_ST_DATA_NACK: // received nack, we are done + case TW_ST_LAST_DATA: // received ack, but we are done already! + // ack future responses + twi_reply(1); + // leave slave receiver state + twi_state = TWI_READY; + break; + */ + + // all + case TW_NO_INFO: // no state information + break; + + case TW_BUS_ERROR: // bus error, illegal stop/start + twi_error = TW_BUS_ERROR; + twi_stop(); + break; + } + + if (fNextInterruptFunction) return fNextInterruptFunction(); + } + + TwoWire::TwoWire() { } + + void TwoWire::begin(void) { + rxBufferIndex = 0; + rxBufferLength = 0; + + txBufferIndex = 0; + txBufferLength = 0; + + twi_init(); + } + + void TwoWire::beginTransmission(uint8_t address) { + //beginTransmission((uint8_t)address); + + // indicate that we are transmitting + twi_transmitting = 1; + + // set address of targeted slave + txAddress = address; + + // reset tx buffer iterator vars + txBufferIndex = 0; + txBufferLength = 0; + } + + uint8_t TwoWire::endTransmission(uint16_t timeout) { + // transmit buffer (blocking) + //int8_t ret = + twi_cbendTransmissionDone = NULL; + twi_writeTo(txAddress, txBuffer, txBufferLength, 1); + int8_t ret = twii_WaitForDone(timeout); + + // reset tx buffer iterator vars + txBufferIndex = 0; + txBufferLength = 0; + + // indicate that we are done transmitting + // twi_transmitting = 0; + return ret; + } + + void TwoWire::nbendTransmission(void (*function)(int)) { + twi_cbendTransmissionDone = function; + twi_writeTo(txAddress, txBuffer, txBufferLength, 1); + return; + } + + void TwoWire::send(uint8_t data) { + if (twi_transmitting) { + // in master transmitter mode + // don't bother if buffer is full + if (txBufferLength >= NBWIRE_BUFFER_LENGTH) { + return; + } + + // put byte in tx buffer + txBuffer[txBufferIndex] = data; + ++txBufferIndex; + + // update amount in buffer + txBufferLength = txBufferIndex; + } else { + // in slave send mode + // reply to master + //twi_transmit(&data, 1); + } + } + + uint8_t TwoWire::receive(void) { + // default to returning null char + // for people using with char strings + uint8_t value = 0; + + // get each successive byte on each call + if (rxBufferIndex < rxBufferLength) { + value = rxBuffer[rxBufferIndex]; + ++rxBufferIndex; + } + + return value; + } + + uint8_t TwoWire::requestFrom(uint8_t address, int quantity, uint16_t timeout) { + // clamp to buffer length + if (quantity > NBWIRE_BUFFER_LENGTH) { + quantity = NBWIRE_BUFFER_LENGTH; + } + + // perform blocking read into buffer + twi_cbreadFromDone = NULL; + twi_readFrom(address, rxBuffer, quantity); + uint8_t read = twii_WaitForDone(timeout); + + // set rx buffer iterator vars + rxBufferIndex = 0; + rxBufferLength = read; + + return read; + } + + void TwoWire::nbrequestFrom(uint8_t address, int quantity, void (*function)(int)) { + // clamp to buffer length + if (quantity > NBWIRE_BUFFER_LENGTH) { + quantity = NBWIRE_BUFFER_LENGTH; + } + + // perform blocking read into buffer + twi_cbreadFromDone = function; + twi_readFrom(address, rxBuffer, quantity); + //uint8_t read = twii_WaitForDone(); + + // set rx buffer iterator vars + //rxBufferIndex = 0; + //rxBufferLength = read; + + rxBufferIndex = 0; + rxBufferLength = quantity; // this is a hack + + return; //read; + } + + uint8_t TwoWire::available(void) { + return rxBufferLength - rxBufferIndex; + } + +#endif diff --git a/firmware/lib/imu/I2Cdev.h b/firmware/lib/imu/I2Cdev.h new file mode 100644 index 0000000..eab8ea0 --- /dev/null +++ b/firmware/lib/imu/I2Cdev.h @@ -0,0 +1,280 @@ +// I2Cdev library collection - Main I2C device class header file +// Abstracts bit and byte I2C R/W functions into a convenient class +// 2013-06-05 by Jeff Rowberg +// +// Changelog: +// 2015-10-30 - simondlevy : support i2c_t3 for Teensy3.1 +// 2013-05-06 - add Francesco Ferrara's Fastwire v0.24 implementation with small modifications +// 2013-05-05 - fix issue with writing bit values to words (Sasquatch/Farzanegan) +// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire +// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation +// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums) +// 2011-10-03 - added automatic Arduino version detection for ease of use +// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications +// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x) +// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default +// 2011-08-02 - added support for 16-bit registers +// - fixed incorrect Doxygen comments on some methods +// - added timeout value for read operations (thanks mem @ Arduino forums) +// 2011-07-30 - changed read/write function structures to return success or byte counts +// - made all methods static for multi-device memory savings +// 2011-07-28 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2013 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#ifndef _I2CDEV_H_ +#define _I2CDEV_H_ + +// ----------------------------------------------------------------------------- +// I2C interface implementation setting +// ----------------------------------------------------------------------------- +#ifndef I2CDEV_IMPLEMENTATION +#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE +//#define I2CDEV_IMPLEMENTATION I2CDEV_BUILTIN_FASTWIRE +#endif // I2CDEV_IMPLEMENTATION + +// comment this out if you are using a non-optimal IDE/implementation setting +// but want the compiler to shut up about it +#define I2CDEV_IMPLEMENTATION_WARNINGS + +// ----------------------------------------------------------------------------- +// I2C interface implementation options +// ----------------------------------------------------------------------------- +#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino +#define I2CDEV_BUILTIN_NBWIRE 2 // Tweaked Wire object from Gene Knight's NBWire project + // ^^^ NBWire implementation is still buggy w/some interrupts! +#define I2CDEV_BUILTIN_FASTWIRE 3 // FastWire object from Francesco Ferrara's project +#define I2CDEV_I2CMASTER_LIBRARY 4 // I2C object from DSSCircuits I2C-Master Library at https://github.com/DSSCircuits/I2C-Master-Library + +// ----------------------------------------------------------------------------- +// Arduino-style "Serial.print" debug constant (uncomment to enable) +// ----------------------------------------------------------------------------- +//#define I2CDEV_SERIAL_DEBUG + +#ifdef ARDUINO + #if ARDUINO < 100 + #include "WProgram.h" + #else + #include "Arduino.h" + #endif + #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + #include + #endif + #if I2CDEV_IMPLEMENTATION == I2CDEV_I2CMASTER_LIBRARY + #include + #endif +#endif + +#ifdef SPARK + #include + #define ARDUINO 101 +#endif + +#define BUFFER_LENGTH 32 // added 07.07.2023 + + +// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];") +#define I2CDEV_DEFAULT_READ_TIMEOUT 1000 + +class I2Cdev { + public: + I2Cdev(); + + static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + + static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data); + static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); + static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); + static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); + static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); + static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); + static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); + static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + + static uint16_t readTimeout; +}; + +#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + ////////////////////// + // FastWire 0.24 + // This is a library to help faster programs to read I2C devices. + // Copyright(C) 2012 + // Francesco Ferrara + ////////////////////// + + /* Master */ + #define TW_START 0x08 + #define TW_REP_START 0x10 + + /* Master Transmitter */ + #define TW_MT_SLA_ACK 0x18 + #define TW_MT_SLA_NACK 0x20 + #define TW_MT_DATA_ACK 0x28 + #define TW_MT_DATA_NACK 0x30 + #define TW_MT_ARB_LOST 0x38 + + /* Master Receiver */ + #define TW_MR_ARB_LOST 0x38 + #define TW_MR_SLA_ACK 0x40 + #define TW_MR_SLA_NACK 0x48 + #define TW_MR_DATA_ACK 0x50 + #define TW_MR_DATA_NACK 0x58 + + #define TW_OK 0 + #define TW_ERROR 1 + + class Fastwire { + private: + static boolean waitInt(); + + public: + static void setup(int khz, boolean pullup); + static byte beginTransmission(byte device); + static byte write(byte value); + static byte writeBuf(byte device, byte address, byte *data, byte num); + static byte readBuf(byte device, byte address, byte *data, byte num); + static void reset(); + static byte stop(); + }; +#endif + +#if I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE + // NBWire implementation based heavily on code by Gene Knight + // Originally posted on the Arduino forum at http://arduino.cc/forum/index.php/topic,70705.0.html + // Originally offered to the i2cdevlib project at http://arduino.cc/forum/index.php/topic,68210.30.html + + #define NBWIRE_BUFFER_LENGTH 32 + + class TwoWire { + private: + static uint8_t rxBuffer[]; + static uint8_t rxBufferIndex; + static uint8_t rxBufferLength; + + static uint8_t txAddress; + static uint8_t txBuffer[]; + static uint8_t txBufferIndex; + static uint8_t txBufferLength; + + // static uint8_t transmitting; + static void (*user_onRequest)(void); + static void (*user_onReceive)(int); + static void onRequestService(void); + static void onReceiveService(uint8_t*, int); + + public: + TwoWire(); + void begin(); + void begin(uint8_t); + void begin(int); + void beginTransmission(uint8_t); + //void beginTransmission(int); + uint8_t endTransmission(uint16_t timeout=0); + void nbendTransmission(void (*function)(int)) ; + uint8_t requestFrom(uint8_t, int, uint16_t timeout=0); + //uint8_t requestFrom(int, int); + void nbrequestFrom(uint8_t, int, void (*function)(int)); + void send(uint8_t); + void send(uint8_t*, uint8_t); + //void send(int); + void send(char*); + uint8_t available(void); + uint8_t receive(void); + void onReceive(void (*)(int)); + void onRequest(void (*)(void)); + }; + + #define TWI_READY 0 + #define TWI_MRX 1 + #define TWI_MTX 2 + #define TWI_SRX 3 + #define TWI_STX 4 + + #define TW_WRITE 0 + #define TW_READ 1 + + #define TW_MT_SLA_NACK 0x20 + #define TW_MT_DATA_NACK 0x30 + + #define CPU_FREQ 16000000L + #define TWI_FREQ 100000L + #define TWI_BUFFER_LENGTH 32 + + /* TWI Status is in TWSR, in the top 5 bits: TWS7 - TWS3 */ + + #define TW_STATUS_MASK (_BV(TWS7)|_BV(TWS6)|_BV(TWS5)|_BV(TWS4)|_BV(TWS3)) + #define TW_STATUS (TWSR & TW_STATUS_MASK) + #define TW_START 0x08 + #define TW_REP_START 0x10 + #define TW_MT_SLA_ACK 0x18 + #define TW_MT_SLA_NACK 0x20 + #define TW_MT_DATA_ACK 0x28 + #define TW_MT_DATA_NACK 0x30 + #define TW_MT_ARB_LOST 0x38 + #define TW_MR_ARB_LOST 0x38 + #define TW_MR_SLA_ACK 0x40 + #define TW_MR_SLA_NACK 0x48 + #define TW_MR_DATA_ACK 0x50 + #define TW_MR_DATA_NACK 0x58 + #define TW_ST_SLA_ACK 0xA8 + #define TW_ST_ARB_LOST_SLA_ACK 0xB0 + #define TW_ST_DATA_ACK 0xB8 + #define TW_ST_DATA_NACK 0xC0 + #define TW_ST_LAST_DATA 0xC8 + #define TW_SR_SLA_ACK 0x60 + #define TW_SR_ARB_LOST_SLA_ACK 0x68 + #define TW_SR_GCALL_ACK 0x70 + #define TW_SR_ARB_LOST_GCALL_ACK 0x78 + #define TW_SR_DATA_ACK 0x80 + #define TW_SR_DATA_NACK 0x88 + #define TW_SR_GCALL_DATA_ACK 0x90 + #define TW_SR_GCALL_DATA_NACK 0x98 + #define TW_SR_STOP 0xA0 + #define TW_NO_INFO 0xF8 + #define TW_BUS_ERROR 0x00 + + //#define _MMIO_BYTE(mem_addr) (*(volatile uint8_t *)(mem_addr)) + //#define _SFR_BYTE(sfr) _MMIO_BYTE(_SFR_ADDR(sfr)) + + #ifndef sbi // set bit + #define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit)) + #endif // sbi + + #ifndef cbi // clear bit + #define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit)) + #endif // cbi + + extern TwoWire Wire; + +#endif // I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE + +#endif /* _I2CDEV_H_ */ diff --git a/firmware/lib/imu/ITG3200.cpp b/firmware/lib/imu/ITG3200.cpp new file mode 100644 index 0000000..d34854d --- /dev/null +++ b/firmware/lib/imu/ITG3200.cpp @@ -0,0 +1,521 @@ +// I2Cdev library collection - ITG3200 I2C device class +// Based on InvenSense ITG-3200 datasheet rev. 1.4, 3/30/2010 (PS-ITG-3200A-00-01.4) +// 7/31/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "ITG3200.h" + +/** Default constructor, uses default I2C address. + * @see ITG3200_DEFAULT_ADDRESS + */ +ITG3200::ITG3200() { + devAddr = ITG3200_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see ITG3200_DEFAULT_ADDRESS + * @see ITG3200_ADDRESS_AD0_LOW + * @see ITG3200_ADDRESS_AD0_HIGH + */ +ITG3200::ITG3200(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the gyroscope, so be sure to adjust the power settings + * after you call this method if you want it to enter standby mode, or another + * less demanding mode of operation. This also sets the gyroscope to use the + * X-axis gyro for a clock source. Note that it doesn't have any delays in the + * routine, which means you might want to add ~50ms to be safe if you happen + * to need to read gyro data immediately after initialization. The data will + * flow in either case, but the first reports may have higher error offsets. + */ +void ITG3200::initialize() { + setFullScaleRange(ITG3200_FULLSCALE_2000); + setClockSource(ITG3200_CLOCK_PLL_XGYRO); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool ITG3200::testConnection() { + return getDeviceID() == 0b110100; +} + +// WHO_AM_I register + +/** Get Device ID. + * This register is used to verify the identity of the device (0b110100). + * @return Device ID (should be 0x34, 52 dec, 64 oct) + * @see ITG3200_RA_WHO_AM_I + * @see ITG3200_RA_DEVID_BIT + * @see ITG3200_RA_DEVID_LENGTH + */ +uint8_t ITG3200::getDeviceID() { + I2Cdev::readBits(devAddr, ITG3200_RA_WHO_AM_I, ITG3200_DEVID_BIT, ITG3200_DEVID_LENGTH, buffer); + return buffer[0]; +} +/** Set Device ID. + * Write a new ID into the WHO_AM_I register (no idea why this should ever be + * necessary though). + * @param id New device ID to set. + * @see getDeviceID() + * @see ITG3200_RA_WHO_AM_I + * @see ITG3200_RA_DEVID_BIT + * @see ITG3200_RA_DEVID_LENGTH + */ +void ITG3200::setDeviceID(uint8_t id) { + I2Cdev::writeBits(devAddr, ITG3200_RA_WHO_AM_I, ITG3200_DEVID_BIT, ITG3200_DEVID_LENGTH, id); +} + +// SMPLRT_DIV register + +/** Get sample rate. + * This register determines the sample rate of the ITG-3200 gyros. The gyros' + * outputs are sampled internally at either 1kHz or 8kHz, determined by the + * DLPF_CFG setting (see register 22). This sampling is then filtered digitally + * and delivered into the sensor registers after the number of cycles determined + * by this register. The sample rate is given by the following formula: + * + * F_sample = F_internal / (divider+1), where F_internal is either 1kHz or 8kHz + * + * As an example, if the internal sampling is at 1kHz, then setting this + * register to 7 would give the following: + * + * F_sample = 1kHz / (7 + 1) = 125Hz, or 8ms per sample + * + * @return Current sample rate + * @see setDLPFBandwidth() + * @see ITG3200_RA_SMPLRT_DIV + */ +uint8_t ITG3200::getRate() { + I2Cdev::readByte(devAddr, ITG3200_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set sample rate. + * @param rate New sample rate + * @see getRate() + * @see setDLPFBandwidth() + * @see ITG3200_RA_SMPLRT_DIV + */ +void ITG3200::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, ITG3200_RA_SMPLRT_DIV, rate); +} + +// DLPF_FS register + +/** Set full-scale range. + * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, + * as described in the table below. The power-on-reset value of FS_SEL is 00h. + * Set to 03h for proper operation. + * + * 0 = Reserved + * 1 = Reserved + * 2 = Reserved + * 3 = +/- 2000 degrees/sec + * + * @return Current full-scale range setting + * @see ITG3200_FULLSCALE_2000 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_FS_SEL_BIT + * @see ITG3200_DF_FS_SEL_LENGTH + */ +uint8_t ITG3200::getFullScaleRange() { + I2Cdev::readBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_FS_SEL_BIT, ITG3200_DF_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale range setting. + * @param range New full-scale range value + * @see getFullScaleRange() + * @see ITG3200_FULLSCALE_2000 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_FS_SEL_BIT + * @see ITG3200_DF_FS_SEL_LENGTH + */ +void ITG3200::setFullScaleRange(uint8_t range) { + I2Cdev::writeBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_FS_SEL_BIT, ITG3200_DF_FS_SEL_LENGTH, range); +} +/** Get digital low-pass filter bandwidth. + * 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. + * + * DLPF_CFG | Low-Pass Filter Bandwidth | Internal Sample Rate + * ---------+---------------------------+--------------------- + * 0 | 256Hz | 8kHz + * 1 | 188Hz | 1kHz + * 2 | 98Hz | 1kHz + * 3 | 42Hz | 1kHz + * 4 | 20Hz | 1kHz + * 5 | 10Hz | 1kHz + * 6 | 5Hz | 1kHz + * 7 | Reserved | Reserved + * + * @return DLFP bandwidth setting + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_DLPF_CFG_BIT + * @see ITG3200_DF_DLPF_CFG_LENGTH + */ +uint8_t ITG3200::getDLPFBandwidth() { + I2Cdev::readBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_DLPF_CFG_BIT, ITG3200_DF_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter bandwidth. + * @param bandwidth New DLFP bandwidth setting + * @see getDLPFBandwidth() + * @see ITG3200_DLPF_BW_256 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_DLPF_CFG_BIT + * @see ITG3200_DF_DLPF_CFG_LENGTH + */ +void ITG3200::setDLPFBandwidth(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_DLPF_CFG_BIT, ITG3200_DF_DLPF_CFG_LENGTH, bandwidth); +} + +// INT_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 ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ACTL_BIT + */ +bool ITG3200::getInterruptMode() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ACTL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ACTL_BIT + */ +void ITG3200::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ACTL_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 ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_OPEN_BIT + */ +bool ITG3200::getInterruptDrive() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_OPEN_BIT + */ +void ITG3200::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_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 ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_LATCH_INT_EN_BIT + */ +bool ITG3200::getInterruptLatch() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_LATCH_INT_EN_BIT + */ +void ITG3200::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_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 ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT + */ +bool ITG3200::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT + */ +void ITG3200::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT, clear); +} +/** Get "device ready" interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ITG_RDY_EN_BIT + */ +bool ITG3200::getIntDeviceReadyEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ITG_RDY_EN_BIT, buffer); + return buffer[0]; +} +/** Set "device ready" interrupt enabled setting. + * @param enabled New interrupt enabled setting + * @see getIntDeviceReadyEnabled() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ITG_RDY_EN_BIT + */ +void ITG3200::setIntDeviceReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ITG_RDY_EN_BIT, enabled); +} +/** Get "data ready" interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_RAW_RDY_EN_BIT + */ +bool ITG3200::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_RAW_RDY_EN_BIT, buffer); + return buffer[0]; +} +/** Set "data ready" interrupt enabled setting. + * @param enabled New interrupt enabled setting + * @see getIntDataReadyEnabled() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_RAW_RDY_EN_BIT + */ +void ITG3200::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_RAW_RDY_EN_BIT, enabled); +} + +// INT_STATUS register + +/** Get Device Ready interrupt status. + * The ITG_RDY interrupt indicates that the PLL is ready and gyroscopic data can + * be read. + * @return Device Ready interrupt status + * @see ITG3200_RA_INT_STATUS + * @see ITG3200_INTSTAT_RAW_DATA_READY_BIT + */ +bool ITG3200::getIntDeviceReadyStatus() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_STATUS, ITG3200_INTSTAT_ITG_RDY_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * In normal use, the RAW_DATA_RDY interrupt is used to determine when new + * sensor data is available in and of the sensor registers (27 to 32). + * @return Data Ready interrupt status + * @see ITG3200_RA_INT_STATUS + * @see ITG3200_INTSTAT_RAW_DATA_READY_BIT + */ +bool ITG3200::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_STATUS, ITG3200_INTSTAT_RAW_DATA_READY_BIT, buffer); + return buffer[0]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see ITG3200_RA_TEMP_OUT_H + */ +int16_t ITG3200::getTemperature() { + I2Cdev::readBytes(devAddr, ITG3200_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// GYRO_*OUT_* registers + +/** Get 3-axis gyroscope readings. + * @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 ITG3200_RA_GYRO_XOUT_H + */ +void ITG3200::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_XOUT_H + */ +int16_t ITG3200::getRotationX() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_YOUT_H + */ +int16_t ITG3200::getRotationY() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_ZOUT_H + */ +int16_t ITG3200::getRotationZ() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// PWR_MGM register + +/** Trigger a full device reset. + * A small delay of ~50ms may be desirable after triggering a reset. + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_H_RESET_BIT + */ +void ITG3200::reset() { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_H_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 ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_SLEEP_BIT + */ +bool ITG3200::getSleepEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_SLEEP_BIT + */ +void ITG3200::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_SLEEP_BIT, enabled); +} +/** Get X-axis 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 ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_XG_BIT + */ +bool ITG3200::getStandbyXEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_XG_BIT, buffer); + return buffer[0]; +} +/** Set X-axis standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_XG_BIT + */ +void ITG3200::setStandbyXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_XG_BIT, enabled); +} +/** Get Y-axis 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 ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_YG_BIT + */ +bool ITG3200::getStandbyYEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_YG_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_YG_BIT + */ +void ITG3200::setStandbyYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_YG_BIT, enabled); +} +/** Get Z-axis 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 ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_ZG_BIT + */ +bool ITG3200::getStandbyZEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_ZG_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_ZG_BIT + */ +void ITG3200::setStandbyZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_ZG_BIT, enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_CLK_SEL_BIT + * @see ITG3200_PWR_CLK_SEL_LENGTH + */ +uint8_t ITG3200::getClockSource() { + I2Cdev::readBits(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_CLK_SEL_BIT, ITG3200_PWR_CLK_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * On power up, the ITG-3200 defaults to the internal oscillator. It is highly recommended that the device is configured to use one of the gyros (or an external clock) as the clock reference, due to the improved stability. + * + * The CLK_SEL setting determines the device clock source as follows: + * + * 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 | Reserved + * + * @param source New clock source setting + * @see getClockSource() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_CLK_SEL_BIT + * @see ITG3200_PWR_CLK_SEL_LENGTH + */ +void ITG3200::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_CLK_SEL_BIT, ITG3200_PWR_CLK_SEL_LENGTH, source); +} diff --git a/firmware/lib/imu/ITG3200.h b/firmware/lib/imu/ITG3200.h new file mode 100644 index 0000000..6a40039 --- /dev/null +++ b/firmware/lib/imu/ITG3200.h @@ -0,0 +1,179 @@ +// I2Cdev library collection - ITG3200 I2C device class header file +// Based on InvenSense ITG-3200 datasheet rev. 1.4, 3/30/2010 (PS-ITG-3200A-00-01.4) +// 7/31/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#ifndef _ITG3200_H_ +#define _ITG3200_H_ + +#include "I2Cdev.h" + +#define ITG3200_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for SparkFun IMU Digital Combo board +#define ITG3200_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC), default for SparkFun ITG-3200 Breakout board +#define ITG3200_DEFAULT_ADDRESS ITG3200_ADDRESS_AD0_LOW + +#define ITG3200_RA_WHO_AM_I 0x00 +#define ITG3200_RA_SMPLRT_DIV 0x15 +#define ITG3200_RA_DLPF_FS 0x16 +#define ITG3200_RA_INT_CFG 0x17 +#define ITG3200_RA_INT_STATUS 0x1A +#define ITG3200_RA_TEMP_OUT_H 0x1B +#define ITG3200_RA_TEMP_OUT_L 0x1C +#define ITG3200_RA_GYRO_XOUT_H 0x1D +#define ITG3200_RA_GYRO_XOUT_L 0x1E +#define ITG3200_RA_GYRO_YOUT_H 0x1F +#define ITG3200_RA_GYRO_YOUT_L 0x20 +#define ITG3200_RA_GYRO_ZOUT_H 0x21 +#define ITG3200_RA_GYRO_ZOUT_L 0x22 +#define ITG3200_RA_PWR_MGM 0x3E + +#define ITG3200_DEVID_BIT 6 +#define ITG3200_DEVID_LENGTH 6 + +#define ITG3200_DF_FS_SEL_BIT 4 +#define ITG3200_DF_FS_SEL_LENGTH 2 +#define ITG3200_DF_DLPF_CFG_BIT 2 +#define ITG3200_DF_DLPF_CFG_LENGTH 3 + +#define ITG3200_FULLSCALE_2000 0x03 + +#define ITG3200_DLPF_BW_256 0x00 +#define ITG3200_DLPF_BW_188 0x01 +#define ITG3200_DLPF_BW_98 0x02 +#define ITG3200_DLPF_BW_42 0x03 +#define ITG3200_DLPF_BW_20 0x04 +#define ITG3200_DLPF_BW_10 0x05 +#define ITG3200_DLPF_BW_5 0x06 + +#define ITG3200_INTCFG_ACTL_BIT 7 +#define ITG3200_INTCFG_OPEN_BIT 6 +#define ITG3200_INTCFG_LATCH_INT_EN_BIT 5 +#define ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT 4 +#define ITG3200_INTCFG_ITG_RDY_EN_BIT 2 +#define ITG3200_INTCFG_RAW_RDY_EN_BIT 0 + +#define ITG3200_INTMODE_ACTIVEHIGH 0x00 +#define ITG3200_INTMODE_ACTIVELOW 0x01 + +#define ITG3200_INTDRV_PUSHPULL 0x00 +#define ITG3200_INTDRV_OPENDRAIN 0x01 + +#define ITG3200_INTLATCH_50USPULSE 0x00 +#define ITG3200_INTLATCH_WAITCLEAR 0x01 + +#define ITG3200_INTCLEAR_STATUSREAD 0x00 +#define ITG3200_INTCLEAR_ANYREAD 0x01 + +#define ITG3200_INTSTAT_ITG_RDY_BIT 2 +#define ITG3200_INTSTAT_RAW_DATA_READY_BIT 0 + +#define ITG3200_PWR_H_RESET_BIT 7 +#define ITG3200_PWR_SLEEP_BIT 6 +#define ITG3200_PWR_STBY_XG_BIT 5 +#define ITG3200_PWR_STBY_YG_BIT 4 +#define ITG3200_PWR_STBY_ZG_BIT 3 +#define ITG3200_PWR_CLK_SEL_BIT 2 +#define ITG3200_PWR_CLK_SEL_LENGTH 3 + +#define ITG3200_CLOCK_INTERNAL 0x00 +#define ITG3200_CLOCK_PLL_XGYRO 0x01 +#define ITG3200_CLOCK_PLL_YGYRO 0x02 +#define ITG3200_CLOCK_PLL_ZGYRO 0x03 +#define ITG3200_CLOCK_PLL_EXT32K 0x04 +#define ITG3200_CLOCK_PLL_EXT19M 0x05 + +class ITG3200 { + public: + ITG3200(); + ITG3200(uint8_t address); + + void initialize(); + bool testConnection(); + + // WHO_AM_I register + uint8_t getDeviceID(); + void setDeviceID(uint8_t id); + + // SMPLRT_DIV register + uint8_t getRate(); + void setRate(uint8_t rate); + + // DLPF_FS register + uint8_t getFullScaleRange(); + void setFullScaleRange(uint8_t range); + uint8_t getDLPFBandwidth(); + void setDLPFBandwidth(uint8_t bandwidth); + + // INT_CFG register + bool getInterruptMode(); + void setInterruptMode(bool mode); + bool getInterruptDrive(); + void setInterruptDrive(bool drive); + bool getInterruptLatch(); + void setInterruptLatch(bool latch); + bool getInterruptLatchClear(); + void setInterruptLatchClear(bool clear); + bool getIntDeviceReadyEnabled(); + void setIntDeviceReadyEnabled(bool enabled); + bool getIntDataReadyEnabled(); + void setIntDataReadyEnabled(bool enabled); + + // INT_STATUS register + bool getIntDeviceReadyStatus(); + bool getIntDataReadyStatus(); + + // TEMP_OUT_* registers + int16_t getTemperature(); + + // GYRO_*OUT_* registers + void getRotation(int16_t* x, int16_t* y, int16_t* z); + int16_t getRotationX(); + int16_t getRotationY(); + int16_t getRotationZ(); + + // PWR_MGM register + void reset(); + bool getSleepEnabled(); + void setSleepEnabled(bool enabled); + bool getStandbyXEnabled(); + void setStandbyXEnabled(bool enabled); + bool getStandbyYEnabled(); + void setStandbyYEnabled(bool enabled); + bool getStandbyZEnabled(); + void setStandbyZEnabled(bool enabled); + uint8_t getClockSource(); + void setClockSource(uint8_t source); + + private: + uint8_t devAddr; + uint8_t buffer[6]; +}; + +#endif /* _ITG3200_H_ */ diff --git a/firmware/lib/imu/MPU6050.cpp b/firmware/lib/imu/MPU6050.cpp new file mode 100644 index 0000000..72d8d86 --- /dev/null +++ b/firmware/lib/imu/MPU6050.cpp @@ -0,0 +1,3213 @@ +// I2Cdev library collection - MPU6050 I2C device class +// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 8/24/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "MPU6050.h" + +/** Default constructor, uses default I2C address. + * @see MPU6050_DEFAULT_ADDRESS + */ +MPU6050::MPU6050() { + devAddr = MPU6050_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see MPU6050_DEFAULT_ADDRESS + * @see MPU6050_ADDRESS_AD0_LOW + * @see MPU6050_ADDRESS_AD0_HIGH + */ +MPU6050::MPU6050(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the device and take it out of sleep mode (which must be done + * after start-up). This function also sets both the accelerometer and the gyroscope + * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets + * the clock source to use the X Gyro for reference, which is slightly better than + * the default internal clock source. + */ +void MPU6050::initialize() { + setClockSource(MPU6050_CLOCK_PLL_XGYRO); + setFullScaleGyroRange(MPU6050_GYRO_FS_250); + setFullScaleAccelRange(MPU6050_ACCEL_FS_2); + setSleepEnabled(false); // thanks to Jack Elston for pointing this one out! +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool MPU6050::testConnection() { + return getDeviceID() == 0x34; +} + +// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC) + +/** Get the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @return I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +uint8_t MPU6050::getAuxVDDIOLevel() { + I2Cdev::readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer); + return buffer[0]; +} +/** Set the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @param level I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +void MPU6050::setAuxVDDIOLevel(uint8_t level) { + I2Cdev::writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level); +} + +// SMPLRT_DIV register + +/** Get gyroscope output rate divider. + * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero + * Motion detection, and Free Fall detection are all based on the Sample Rate. + * The Sample Rate is generated by dividing the gyroscope output rate by + * SMPLRT_DIV: + * + * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) + * + * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or + * 7), and 1kHz when the DLPF is enabled (see Register 26). + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + * For a diagram of the gyroscope and accelerometer signal paths, see Section 8 + * of the MPU-6000/MPU-6050 Product Specification document. + * + * @return Current sample rate + * @see MPU6050_RA_SMPLRT_DIV + */ +uint8_t MPU6050::getRate() { + I2Cdev::readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set gyroscope sample rate divider. + * @param rate New sample rate divider + * @see getRate() + * @see MPU6050_RA_SMPLRT_DIV + */ +void MPU6050::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate); +} + +// CONFIG register + +/** Get external FSYNC configuration. + * Configures the external Frame Synchronization (FSYNC) pin sampling. An + * external signal connected to the FSYNC pin can be sampled by configuring + * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short + * strobes may be captured. The latched FSYNC signal will be sampled at the + * Sampling Rate, as defined in register 25. After sampling, the latch will + * reset to the current FSYNC signal state. + * + * The sampled value will be reported in place of the least significant bit in + * a sensor data register determined by the value of EXT_SYNC_SET according to + * the following table. + * + *
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * 
+ * + * @return FSYNC configuration value + */ +uint8_t MPU6050::getExternalFrameSync() { + I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer); + return buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see MPU6050_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void MPU6050::setExternalFrameSync(uint8_t sync) { + I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync); +} +/** Get digital low-pass filter configuration. + * The DLPF_CFG parameter sets the digital low pass filter configuration. It + * also determines the internal sampling rate used by the device as shown in + * the table below. + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + *
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * 
+ * + * @return DLFP configuration + * @see MPU6050_RA_CONFIG + * @see MPU6050_CFG_DLPF_CFG_BIT + * @see MPU6050_CFG_DLPF_CFG_LENGTH + */ +uint8_t MPU6050::getDLPFMode() { + I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see MPU6050_DLPF_BW_256 + * @see MPU6050_RA_CONFIG + * @see MPU6050_CFG_DLPF_CFG_BIT + * @see MPU6050_CFG_DLPF_CFG_LENGTH + */ +void MPU6050::setDLPFMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode); +} + +// GYRO_CONFIG register + +/** Get full-scale gyroscope range. + * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, + * as described in the table below. + * + *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * 
+ * + * @return Current full-scale gyroscope range setting + * @see MPU6050_GYRO_FS_250 + * @see MPU6050_RA_GYRO_CONFIG + * @see MPU6050_GCONFIG_FS_SEL_BIT + * @see MPU6050_GCONFIG_FS_SEL_LENGTH + */ +uint8_t MPU6050::getFullScaleGyroRange() { + I2Cdev::readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see MPU6050_GYRO_FS_250 + * @see MPU6050_RA_GYRO_CONFIG + * @see MPU6050_GCONFIG_FS_SEL_BIT + * @see MPU6050_GCONFIG_FS_SEL_LENGTH + */ +void MPU6050::setFullScaleGyroRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range); +} + +// SELF TEST FACTORY TRIM VALUES + +/** Get self-test factory trim value for accelerometer X axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_X + */ +uint8_t MPU6050::getAccelXSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, &buffer[0]); + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1]); + return (buffer[0]>>3) | ((buffer[1]>>4) & 0x03); +} + +/** Get self-test factory trim value for accelerometer Y axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Y + */ +uint8_t MPU6050::getAccelYSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, &buffer[0]); + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1]); + return (buffer[0]>>3) | ((buffer[1]>>2) & 0x03); +} + +/** Get self-test factory trim value for accelerometer Z axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Z + */ +uint8_t MPU6050::getAccelZSelfTestFactoryTrim() { + I2Cdev::readBytes(devAddr, MPU6050_RA_SELF_TEST_Z, 2, buffer); + return (buffer[0]>>3) | (buffer[1] & 0x03); +} + +/** Get self-test factory trim value for gyro X axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_X + */ +uint8_t MPU6050::getGyroXSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, buffer); + return (buffer[0] & 0x1F); +} + +/** Get self-test factory trim value for gyro Y axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Y + */ +uint8_t MPU6050::getGyroYSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, buffer); + return (buffer[0] & 0x1F); +} + +/** Get self-test factory trim value for gyro Z axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Z + */ +uint8_t MPU6050::getGyroZSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Z, buffer); + return (buffer[0] & 0x1F); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelXSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelXSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelYSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelYSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelZSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer); + return buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelZSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled); +} +/** Get full-scale accelerometer range. + * The FS_SEL parameter allows setting the full-scale range of the accelerometer + * sensors, as described in the table below. + * + *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * 
+ * + * @return Current full-scale accelerometer range setting + * @see MPU6050_ACCEL_FS_2 + * @see MPU6050_RA_ACCEL_CONFIG + * @see MPU6050_ACONFIG_AFS_SEL_BIT + * @see MPU6050_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t MPU6050::getFullScaleAccelRange() { + I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void MPU6050::setFullScaleAccelRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range); +} +/** Get the high-pass filter configuration. + * The DHPF is a filter module in the path leading to motion detectors (Free + * Fall, Motion threshold, and Zero Motion). The high pass filter output is not + * available to the data registers (see Figure in Section 8 of the MPU-6000/ + * MPU-6050 Product Specification document). + * + * The high pass filter has three modes: + * + *
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * 
+ * + *
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * 
+ * + * @return Current high-pass filter configuration + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +uint8_t MPU6050::getDHPFMode() { + I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer); + return buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setDHPFMode(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth); +} + +// FF_THR register + +/** Get free-fall event acceleration threshold. + * This register configures the detection threshold for Free Fall event + * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the + * absolute value of the accelerometer measurements for the three axes are each + * less than the detection threshold. This condition increments the Free Fall + * duration counter (Register 30). The Free Fall interrupt is triggered when the + * Free Fall duration counter reaches the time specified in FF_DUR. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of the + * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current free-fall acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_FF_THR + */ +uint8_t MPU6050::getFreefallDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_FF_THR, buffer); + return buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see MPU6050_RA_FF_THR + */ +void MPU6050::setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FF_THR, threshold); +} + +// FF_DUR register + +/** Get free-fall event duration threshold. + * This register configures the duration counter threshold for Free Fall event + * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit + * of 1 LSB = 1 ms. + * + * The Free Fall duration counter increments while the absolute value of the + * accelerometer measurements are each less than the detection threshold + * (Register 29). The Free Fall interrupt is triggered when the Free Fall + * duration counter reaches the time specified in this register. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of + * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current free-fall duration threshold value (LSB = 1ms) + * @see MPU6050_RA_FF_DUR + */ +uint8_t MPU6050::getFreefallDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_FF_DUR, buffer); + return buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see MPU6050_RA_FF_DUR + */ +void MPU6050::setFreefallDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FF_DUR, duration); +} + +// MOT_THR register + +/** Get motion detection event acceleration threshold. + * This register configures the detection threshold for Motion interrupt + * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the + * absolute value of any of the accelerometer measurements exceeds this Motion + * detection threshold. This condition increments the Motion detection duration + * counter (Register 32). The Motion detection interrupt is triggered when the + * Motion Detection counter reaches the time count specified in MOT_DUR + * (Register 32). + * + * The Motion interrupt will indicate the axis and polarity of detected motion + * in MOT_DETECT_STATUS (Register 97). + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current motion detection acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_MOT_THR + */ +uint8_t MPU6050::getMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_THR, buffer); + return buffer[0]; +} +/** Set motion detection event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see MPU6050_RA_MOT_THR + */ +void MPU6050::setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_THR, threshold); +} + +// MOT_DUR register + +/** Get motion detection event duration threshold. + * This register configures the duration counter threshold for Motion interrupt + * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit + * of 1LSB = 1ms. The Motion detection duration counter increments when the + * absolute value of any of the accelerometer measurements exceeds the Motion + * detection threshold (Register 31). The Motion detection interrupt is + * triggered when the Motion detection counter reaches the time count specified + * in this register. + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-6050 Product Specification document. + * + * @return Current motion detection duration threshold value (LSB = 1ms) + * @see MPU6050_RA_MOT_DUR + */ +uint8_t MPU6050::getMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DUR, buffer); + return buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see MPU6050_RA_MOT_DUR + */ +void MPU6050::setMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_DUR, duration); +} + +// ZRMOT_THR register + +/** Get zero motion detection event acceleration threshold. + * This register configures the detection threshold for Zero Motion interrupt + * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when + * the absolute value of the accelerometer measurements for the 3 axes are each + * less than the detection threshold. This condition increments the Zero Motion + * duration counter (Register 34). The Zero Motion interrupt is triggered when + * the Zero Motion duration counter reaches the time count specified in + * ZRMOT_DUR (Register 34). + * + * Unlike Free Fall or Motion detection, Zero Motion detection triggers an + * interrupt both when Zero Motion is first detected and when Zero Motion is no + * longer detected. + * + * When a zero motion event is detected, a Zero Motion Status will be indicated + * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion + * condition is detected, the status bit is set to 1. When a zero-motion-to- + * motion condition is detected, the status bit is set to 0. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_ZRMOT_THR + */ +uint8_t MPU6050::getZeroMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer); + return buffer[0]; +} +/** Set zero motion detection event acceleration threshold. + * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) + * @see getZeroMotionDetectionThreshold() + * @see MPU6050_RA_ZRMOT_THR + */ +void MPU6050::setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold); +} + +// ZRMOT_DUR register + +/** Get zero motion detection event duration threshold. + * This register configures the duration counter threshold for Zero Motion + * interrupt generation. The duration counter ticks at 16 Hz, therefore + * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter + * increments while the absolute value of the accelerometer measurements are + * each less than the detection threshold (Register 33). The Zero Motion + * interrupt is triggered when the Zero Motion duration counter reaches the time + * count specified in this register. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection duration threshold value (LSB = 64ms) + * @see MPU6050_RA_ZRMOT_DUR + */ +uint8_t MPU6050::getZeroMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer); + return buffer[0]; +} +/** Set zero motion detection event duration threshold. + * @param duration New zero motion detection duration threshold value (LSB = 1ms) + * @see getZeroMotionDetectionDuration() + * @see MPU6050_RA_ZRMOT_DUR + */ +void MPU6050::setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration); +} + +// FIFO_EN register + +/** Get temperature FIFO enabled value. + * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and + * 66) to be written into the FIFO buffer. + * @return Current temperature FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getTempFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setTempFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled); +} +/** Get gyroscope X-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and + * 68) to be written into the FIFO buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getXGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setXGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Y-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and + * 70) to be written into the FIFO buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getYGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setYGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Z-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and + * 72) to be written into the FIFO buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getZGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setZGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled); +} +/** Get accelerometer FIFO enabled value. + * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, + * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be + * written into the FIFO buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled); +} +/** Get Slave 2 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 2 to be written into the FIFO buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave2FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave2FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled); +} +/** Get Slave 1 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 1 to be written into the FIFO buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave1FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave1FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled); +} +/** Get Slave 0 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 0 to be written into the FIFO buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave0FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave0FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled); +} + +// I2C_MST_CTRL register + +/** Get multi-master enabled value. + * Multi-master capability allows multiple I2C masters to operate on the same + * bus. In circuits where multi-master capability is required, set MULT_MST_EN + * to 1. This will increase current drawn by approximately 30uA. + * + * In circuits where multi-master capability is required, the state of the I2C + * bus must always be monitored by each separate I2C Master. Before an I2C + * Master can assume arbitration of the bus, it must first confirm that no other + * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the + * MPU-60X0's bus arbitration detection logic is turned on, enabling it to + * detect when the bus is available. + * + * @return Current multi-master enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getMultiMasterEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setMultiMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled); +} +/** Get wait-for-external-sensor-data enabled value. + * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be + * delayed until External Sensor data from the Slave Devices are loaded into the + * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor + * data (i.e. from gyro and accel) and external sensor data have been loaded to + * their respective data registers (i.e. the data is synced) when the Data Ready + * interrupt is triggered. + * + * @return Current wait-for-external-sensor-data enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getWaitForExternalSensorEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer); + return buffer[0]; +} +/** Set wait-for-external-sensor-data enabled value. + * @param enabled New wait-for-external-sensor-data enabled value + * @see getWaitForExternalSensorEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled); +} +/** Get Slave 3 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 3 to be written into the FIFO buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU6050_RA_MST_CTRL + */ +bool MPU6050::getSlave3FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see MPU6050_RA_MST_CTRL + */ +void MPU6050::setSlave3FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled); +} +/** Get slave read/write transition enabled value. + * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave + * read to the next slave read. If the bit equals 0, there will be a restart + * between reads. If the bit equals 1, there will be a stop followed by a start + * of the following read. When a write transaction follows a read transaction, + * the stop followed by a start of the successive write will be always used. + * + * @return Current slave read/write transition enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getSlaveReadWriteTransitionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer); + return buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled); +} +/** Get I2C master clock speed. + * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the + * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to + * the following table: + * + *
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * 
+ * + * @return Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +uint8_t MPU6050::getMasterClockSpeed() { + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer); + return buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setMasterClockSpeed(uint8_t speed) { + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed); +} + +// I2C_SLV* registers (Slave 0-3) + +/** Get the I2C address of the specified slave (0-3). + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * In read mode, the result of the read is placed in the lowest available + * EXT_SENS_DATA register. For further information regarding the allocation of + * read results, please refer to the EXT_SENS_DATA register description + * (Registers 73 - 96). + * + * The MPU-6050 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions (getSlave4* and setSlave4*). + * + * I2C data transactions are performed at the Sample Rate, as defined in + * Register 25. The user is responsible for ensuring that I2C data transactions + * to and from each enabled Slave can be completed within a single period of the + * Sample Rate. + * + * The I2C slave access rate can be reduced relative to the Sample Rate. This + * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a + * slave's access rate is reduced relative to the Sample Rate is determined by + * I2C_MST_DELAY_CTRL (Register 103). + * + * The processing order for the slaves is fixed. The sequence followed for + * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a + * particular Slave is disabled it will be skipped. + * + * Each slave can either be accessed at the sample rate or at a reduced sample + * rate. In a case where some slaves are accessed at the Sample Rate and some + * slaves are accessed at the reduced rate, the sequence of accessing the slaves + * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will + * be skipped if their access rate dictates that they should not be accessed + * during that particular cycle. For further information regarding the reduced + * access rate, please refer to Register 52. Whether a slave is accessed at the + * Sample Rate or at the reduced rate is determined by the Delay Enable bits in + * Register 103. + * + * @param num Slave number (0-3) + * @return Current address for specified slave + * @see MPU6050_RA_I2C_SLV0_ADDR + */ +uint8_t MPU6050::getSlaveAddress(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer); + return buffer[0]; +} +/** Set the I2C address of the specified slave (0-3). + * @param num Slave number (0-3) + * @param address New address for specified slave + * @see getSlaveAddress() + * @see MPU6050_RA_I2C_SLV0_ADDR + */ +void MPU6050::setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address); +} +/** Get the active internal register for the specified slave (0-3). + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * The MPU-6050 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions. + * + * @param num Slave number (0-3) + * @return Current active register for specified slave + * @see MPU6050_RA_I2C_SLV0_REG + */ +uint8_t MPU6050::getSlaveRegister(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer); + return buffer[0]; +} +/** Set the active internal register for the specified slave (0-3). + * @param num Slave number (0-3) + * @param reg New active register for specified slave + * @see getSlaveRegister() + * @see MPU6050_RA_I2C_SLV0_REG + */ +void MPU6050::setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg); +} +/** Get the enabled value for the specified slave (0-3). + * When set to 1, this bit enables Slave 0 for data transfer operations. When + * cleared to 0, this bit disables Slave 0 from data transfer operations. + * @param num Slave number (0-3) + * @return Current enabled value for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveEnabled(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New enabled value for specified slave + * @see getSlaveEnabled() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled); +} +/** Get word pair byte-swapping enabled for the specified slave (0-3). + * When set to 1, this bit enables byte swapping. When byte swapping is enabled, + * the high and low bytes of a word pair are swapped. Please refer to + * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0, + * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA + * registers in the order they were transferred. + * + * @param num Slave number (0-3) + * @return Current word pair byte-swapping enabled value for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWordByteSwap(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer); + return buffer[0]; +} +/** Set word pair byte-swapping enabled for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair byte-swapping enabled value for specified slave + * @see getSlaveWordByteSwap() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled); +} +/** Get write mode for the specified slave (0-3). + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @param num Slave number (0-3) + * @return Current write mode for specified slave (0 = register address + data, 1 = data only) + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWriteMode(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the specified slave (0-3). + * @param num Slave number (0-3) + * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) + * @see getSlaveWriteMode() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode); +} +/** Get word pair grouping order offset for the specified slave (0-3). + * This sets specifies the grouping order of word pairs received from registers. + * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even, + * then odd register addresses) are paired to form a word. When set to 1, bytes + * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even + * register addresses) are paired to form a word. + * + * @param num Slave number (0-3) + * @return Current word pair grouping order offset for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer); + return buffer[0]; +} +/** Set word pair grouping order offset for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair grouping order offset for specified slave + * @see getSlaveWordGroupOffset() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled); +} +/** Get number of bytes to read for the specified slave (0-3). + * Specifies the number of bytes transferred to and from Slave 0. Clearing this + * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN. + * @param num Slave number (0-3) + * @return Number of bytes to read for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +uint8_t MPU6050::getSlaveDataLength(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer); + return buffer[0]; +} +/** Set number of bytes to read for the specified slave (0-3). + * @param num Slave number (0-3) + * @param length Number of bytes to read for specified slave + * @see getSlaveDataLength() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) return; + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length); +} + +// I2C_SLV* registers (Slave 4) + +/** Get the I2C address of Slave 4. + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * @return Current address for Slave 4 + * @see getSlaveAddress() + * @see MPU6050_RA_I2C_SLV4_ADDR + */ +uint8_t MPU6050::getSlave4Address() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer); + return buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see MPU6050_RA_I2C_SLV4_ADDR + */ +void MPU6050::setSlave4Address(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address); +} +/** Get the active internal register for the Slave 4. + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * @return Current active register for Slave 4 + * @see MPU6050_RA_I2C_SLV4_REG + */ +uint8_t MPU6050::getSlave4Register() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer); + return buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see MPU6050_RA_I2C_SLV4_REG + */ +void MPU6050::setSlave4Register(uint8_t reg) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg); +} +/** Set new byte to write to Slave 4. + * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW + * is set 1 (set to read), this register has no effect. + * @param data New byte to write to Slave 4 + * @see MPU6050_RA_I2C_SLV4_DO + */ +void MPU6050::setSlave4OutputByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data); +} +/** Get the enabled value for the Slave 4. + * When set to 1, this bit enables Slave 4 for data transfer operations. When + * cleared to 0, this bit disables Slave 4 from data transfer operations. + * @return Current enabled value for Slave 4 + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4Enabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4Enabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled); +} +/** Get the enabled value for Slave 4 transaction interrupts. + * When set to 1, this bit enables the generation of an interrupt signal upon + * completion of a Slave 4 transaction. When cleared to 0, this bit disables the + * generation of an interrupt signal upon completion of a Slave 4 transaction. + * The interrupt status can be observed in Register 54. + * + * @return Current enabled value for Slave 4 transaction interrupts. + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4InterruptEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4 transaction interrupts. + * @param enabled New enabled value for Slave 4 transaction interrupts. + * @see getSlave4InterruptEnabled() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled); +} +/** Get write mode for Slave 4. + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4WriteMode() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the Slave 4. + * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see getSlave4WriteMode() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4WriteMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode); +} +/** Get Slave 4 master delay value. + * This configures the reduced access rate of I2C slaves relative to the Sample + * Rate. When a slave's access rate is decreased relative to the Sample Rate, + * the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and + * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to + * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For + * further information regarding the Sample Rate, please refer to register 25. + * + * @return Current Slave 4 master delay value + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +uint8_t MPU6050::getSlave4MasterDelay() { + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer); + return buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4MasterDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay); +} +/** Get last available byte read from Slave 4. + * This register stores the data read from Slave 4. This field is populated + * after a read transaction. + * @return Last available byte read from to Slave 4 + * @see MPU6050_RA_I2C_SLV4_DI + */ +uint8_t MPU6050::getSlate4InputByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer); + return buffer[0]; +} + +// I2C_MST_STATUS register + +/** Get FSYNC interrupt status. + * This bit reflects the status of the FSYNC interrupt from an external device + * into the MPU-60X0. This is used as a way to pass an external interrupt + * through the MPU-60X0 to the host application processor. When set to 1, this + * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG + * (Register 55). + * @return FSYNC interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getPassthroughStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 transaction done status. + * Automatically sets to 1 when a Slave 4 transaction has completed. This + * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register + * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the + * I2C_SLV4_CTRL register (Register 52). + * @return Slave 4 transaction done status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave4IsDone() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer); + return buffer[0]; +} +/** Get master arbitration lost status. + * This bit automatically sets to 1 when the I2C Master has lost arbitration of + * the auxiliary I2C bus (an error condition). This triggers an interrupt if the + * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. + * @return Master arbitration lost status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getLostArbitration() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 4 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave4Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 3 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 3 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave3Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 2 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 2 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave2Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 1 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 1 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave1Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 0 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 0 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave0Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer); + return buffer[0]; +} + +// INT_PIN_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_LEVEL_BIT + */ +bool MPU6050::getInterruptMode() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_LEVEL_BIT + */ +void MPU6050::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode); +} +/** Get interrupt drive mode. + * Will be set 0 for push-pull, 1 for open-drain. + * @return Current interrupt drive mode (0=push-pull, 1=open-drain) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_OPEN_BIT + */ +bool MPU6050::getInterruptDrive() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_OPEN_BIT + */ +void MPU6050::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive); +} +/** Get interrupt latch mode. + * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared. + * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_LATCH_INT_EN_BIT + */ +bool MPU6050::getInterruptLatch() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_LATCH_INT_EN_BIT + */ +void MPU6050::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch); +} +/** Get interrupt latch clear mode. + * Will be set 0 for status-read-only, 1 for any-register-read. + * @return Current latch clear mode (0=status-read-only, 1=any-register-read) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT + */ +bool MPU6050::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT + */ +void MPU6050::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear); +} +/** Get FSYNC interrupt logic level mode. + * @return Current FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool MPU6050::getFSyncInterruptLevel() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC interrupt logic level mode. + * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void MPU6050::setFSyncInterruptLevel(bool level) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level); +} +/** Get FSYNC pin interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT + */ +bool MPU6050::getFSyncInterruptEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT + */ +void MPU6050::setFSyncInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled); +} +/** Get I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @return Current I2C bypass enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT + */ +bool MPU6050::getI2CBypassEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @param enabled New I2C bypass enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT + */ +void MPU6050::setI2CBypassEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled); +} +/** Get reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @return Current reference clock output enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_CLKOUT_EN_BIT + */ +bool MPU6050::getClockOutputEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer); + return buffer[0]; +} +/** Set reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @param enabled New reference clock output enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_CLKOUT_EN_BIT + */ +void MPU6050::setClockOutputEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled); +} + +// INT_ENABLE register + +/** Get full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit will be + * set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +uint8_t MPU6050::getIntEnabled() { + I2Cdev::readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer); + return buffer[0]; +} +/** Set full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit should be + * set 0 for disabled, 1 for enabled. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +void MPU6050::setIntEnabled(uint8_t enabled) { + I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled); +} +/** Get Free Fall interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +bool MPU6050::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +void MPU6050::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled); +} +/** Get Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_MOT_BIT + **/ +bool MPU6050::getIntMotionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_MOT_BIT + **/ +void MPU6050::setIntMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled); +} +/** Get Zero Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_ZMOT_BIT + **/ +bool MPU6050::getIntZeroMotionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_ZMOT_BIT + **/ +void MPU6050::setIntZeroMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled); +} +/** Get FIFO Buffer Overflow interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool MPU6050::getIntFIFOBufferOverflowEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + **/ +void MPU6050::setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled); +} +/** Get I2C Master interrupt enabled status. + * This enables any of the I2C Master interrupt sources to generate an + * interrupt. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + **/ +bool MPU6050::getIntI2CMasterEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + **/ +void MPU6050::setIntI2CMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled); +} +/** Get Data Ready interrupt enabled setting. + * This event occurs each time a write operation to all of the sensor registers + * has been completed. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +bool MPU6050::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see MPU6050_RA_INT_CFG + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +void MPU6050::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled); +} + +// INT_STATUS register + +/** Get full set of interrupt status bits. + * These bits clear to 0 after the register has been read. Very useful + * for getting multiple INT statuses, since each single bit read clears + * all of them because it has to read the whole byte. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + */ +uint8_t MPU6050::getIntStatus() { + I2Cdev::readByte(devAddr, MPU6050_RA_INT_STATUS, buffer); + return buffer[0]; +} +/** Get Free Fall interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_FF_BIT + */ +bool MPU6050::getIntFreefallStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Get Motion Detection interrupt status. + * This bit automatically sets to 1 when a Motion Detection interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_MOT_BIT + */ +bool MPU6050::getIntMotionStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Get Zero Motion Detection interrupt status. + * This bit automatically sets to 1 when a Zero Motion Detection interrupt has + * been generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_ZMOT_BIT + */ +bool MPU6050::getIntZeroMotionStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Get FIFO Buffer Overflow interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + */ +bool MPU6050::getIntFIFOBufferOverflowStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Get I2C Master interrupt status. + * This bit automatically sets to 1 when an I2C Master interrupt has been + * generated. For a list of I2C Master interrupts, please refer to Register 54. + * The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + */ +bool MPU6050::getIntI2CMasterStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * This bit automatically sets to 1 when a Data Ready interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +bool MPU6050::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} + +// ACCEL_*OUT_* registers + +/** Get raw 9-axis motion sensor readings (accel/gyro/compass). + * FUNCTION NOT FULLY IMPLEMENTED YET. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @param mx 16-bit signed integer container for magnetometer X-axis value + * @param my 16-bit signed integer container for magnetometer Y-axis value + * @param mz 16-bit signed integer container for magnetometer Z-axis value + * @see getMotion6() + * @see getAcceleration() + * @see getRotation() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +void MPU6050::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz) { + getMotion6(ax, ay, az, gx, gy, gz); + // TODO: magnetometer integration +} +/** Get raw 6-axis motion sensor readings (accel/gyro). + * Retrieves all currently available motion sensor values. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @see getAcceleration() + * @see getRotation() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +void MPU6050::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer); + *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; + *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; + *az = (((int16_t)buffer[4]) << 8) | buffer[5]; + *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; + *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; + *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; +} +/** Get 3-axis accelerometer readings. + * These registers store the most recent accelerometer measurements. + * Accelerometer measurements are written to these registers at the Sample Rate + * as defined in Register 25. + * + * The accelerometer measurement registers, along with the temperature + * measurement registers, gyroscope measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * + * The data within the accelerometer sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS + * (Register 28). For each full scale setting, the accelerometers' sensitivity + * per LSB in ACCEL_xOUT is shown in the table below: + * + *
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * 
+ * + * @param x 16-bit signed integer container for X-axis acceleration + * @param y 16-bit signed integer container for Y-axis acceleration + * @param z 16-bit signed integer container for Z-axis acceleration + * @see MPU6050_RA_GYRO_XOUT_H + */ +void MPU6050::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +int16_t MPU6050::getAccelerationX() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_YOUT_H + */ +int16_t MPU6050::getAccelerationY() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_ZOUT_H + */ +int16_t MPU6050::getAccelerationZ() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see MPU6050_RA_TEMP_OUT_H + */ +int16_t MPU6050::getTemperature() { + I2Cdev::readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// GYRO_*OUT_* registers + +/** Get 3-axis gyroscope readings. + * These gyroscope measurement registers, along with the accelerometer + * measurement registers, temperature measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * The data within the gyroscope sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL + * (Register 27). For each full scale setting, the gyroscopes' sensitivity per + * LSB in GYRO_xOUT is shown in the table below: + * + *
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * 
+ * + * @param x 16-bit signed integer container for X-axis rotation + * @param y 16-bit signed integer container for Y-axis rotation + * @param z 16-bit signed integer container for Z-axis rotation + * @see getMotion6() + * @see MPU6050_RA_GYRO_XOUT_H + */ +void MPU6050::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_XOUT_H + */ +int16_t MPU6050::getRotationX() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_YOUT_H + */ +int16_t MPU6050::getRotationY() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_ZOUT_H + */ +int16_t MPU6050::getRotationZ() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// EXT_SENS_DATA_* registers + +/** Read single byte from external sensor data register. + * These registers store data read from external sensors by the Slave 0, 1, 2, + * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in + * I2C_SLV4_DI (Register 53). + * + * External sensor data is written to these registers at the Sample Rate as + * defined in Register 25. This access rate can be reduced by using the Slave + * Delay Enable registers (Register 103). + * + * External sensor data registers, along with the gyroscope measurement + * registers, accelerometer measurement registers, and temperature measurement + * registers, are composed of two sets of registers: an internal register set + * and a user-facing read register set. + * + * The data within the external sensors' internal register set is always updated + * at the Sample Rate (or the reduced access rate) whenever the serial interface + * is idle. This guarantees that a burst read of sensor registers will read + * measurements from the same sampling instant. Note that if burst reads are not + * used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Data is placed in these external sensor data registers according to + * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, + * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from + * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as + * defined in Register 25) or delayed rate (if specified in Register 52 and + * 103). During each Sample cycle, slave reads are performed in order of Slave + * number. If all slaves are enabled with more than zero bytes to be read, the + * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. + * + * Each enabled slave will have EXT_SENS_DATA registers associated with it by + * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from + * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may + * change the higher numbered slaves' associated registers. Furthermore, if + * fewer total bytes are being read from the external sensors as a result of + * such a change, then the data remaining in the registers which no longer have + * an associated slave device (i.e. high numbered registers) will remain in + * these previously allocated registers unless reset. + * + * If the sum of the read lengths of all SLVx transactions exceed the number of + * available EXT_SENS_DATA registers, the excess bytes will be dropped. There + * are 24 EXT_SENS_DATA registers and hence the total read lengths between all + * the slaves cannot be greater than 24 or some bytes will be lost. + * + * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further + * information regarding the characteristics of Slave 4, please refer to + * Registers 49 to 53. + * + * EXAMPLE: + * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and + * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that + * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 + * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 + * will be associated with Slave 1. If Slave 2 is enabled as well, registers + * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. + * + * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then + * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 + * instead. + * + * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: + * If a slave is disabled at any time, the space initially allocated to the + * slave in the EXT_SENS_DATA register, will remain associated with that slave. + * This is to avoid dynamic adjustment of the register allocation. + * + * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all + * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). + * + * This above is also true if one of the slaves gets NACKed and stops + * functioning. + * + * @param position Starting position (0-23) + * @return Byte read from register + */ +uint8_t MPU6050::getExternalSensorByte(int position) { + I2Cdev::readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer); + return buffer[0]; +} +/** Read word (2 bytes) from external sensor data registers. + * @param position Starting position (0-21) + * @return Word read from register + * @see getExternalSensorByte() + */ +uint16_t MPU6050::getExternalSensorWord(int position) { + I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} +/** Read double word (4 bytes) from external sensor data registers. + * @param position Starting position (0-20) + * @return Double word read from registers + * @see getExternalSensorByte() + */ +uint32_t MPU6050::getExternalSensorDWord(int position) { + I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer); + return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; +} + +// MOT_DETECT_STATUS register + +/** Get full motion detection status register content (all bits). + * @return Motion detection status byte + * @see MPU6050_RA_MOT_DETECT_STATUS + */ +uint8_t MPU6050::getMotionStatus() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DETECT_STATUS, buffer); + return buffer[0]; +} +/** Get X-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_XNEG_BIT + */ +bool MPU6050::getXNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer); + return buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_XPOS_BIT + */ +bool MPU6050::getXPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_YNEG_BIT + */ +bool MPU6050::getYNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_YPOS_BIT + */ +bool MPU6050::getYPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZNEG_BIT + */ +bool MPU6050::getZNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZPOS_BIT + */ +bool MPU6050::getZPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer); + return buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZRMOT_BIT + */ +bool MPU6050::getZeroMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer); + return buffer[0]; +} + +// I2C_SLV*_DO register + +/** Write byte to Data Output container for specified slave. + * This register holds the output data written into Slave when Slave is set to + * write mode. For further information regarding Slave control, please + * refer to Registers 37 to 39 and immediately following. + * @param num Slave number (0-3) + * @param data Byte to write + * @see MPU6050_RA_I2C_SLV0_DO + */ +void MPU6050::setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data); +} + +// I2C_MST_DELAY_CTRL register + +/** Get external data shadow delay enabled status. + * This register is used to specify the timing of external sensor data + * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external + * sensor data is delayed until all data has been received. + * @return Current external data shadow delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool MPU6050::getExternalShadowDelayEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); + return buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void MPU6050::setExternalShadowDelayEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled); +} +/** Get slave delay enabled status. + * When a particular slave delay is enabled, the rate of access for the that + * slave device is reduced. When a slave's access rate is decreased relative to + * the Sample Rate, the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) Samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25) + * and DLPF_CFG (register 26). + * + * For further information regarding I2C_MST_DLY, please refer to register 52. + * For further information regarding the Sample Rate, please refer to register 25. + * + * @param num Slave number (0-4) + * @return Current slave delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool MPU6050::getSlaveDelayEnabled(uint8_t num) { + // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer); + return buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void MPU6050::setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled); +} + +// SIGNAL_PATH_RESET register + +/** Reset gyroscope signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_GYRO_RESET_BIT + */ +void MPU6050::resetGyroscopePath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true); +} +/** Reset accelerometer signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_ACCEL_RESET_BIT + */ +void MPU6050::resetAccelerometerPath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true); +} +/** Reset temperature sensor signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_TEMP_RESET_BIT + */ +void MPU6050::resetTemperaturePath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true); +} + +// MOT_DETECT_CTRL register + +/** Get accelerometer power-on delay. + * The accelerometer data path provides samples to the sensor registers, Motion + * detection, Zero Motion detection, and Free Fall detection modules. The + * signal path contains filters which must be flushed on wake-up with new + * samples before the detection modules begin operations. The default wake-up + * delay, of 4ms can be lengthened by up to 3ms. This additional delay is + * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select + * any value above zero unless instructed otherwise by InvenSense. Please refer + * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for + * further information regarding the detection modules. + * @return Current accelerometer power-on delay + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t MPU6050::getAccelerometerPowerOnDelay() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); + return buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT + */ +void MPU6050::setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay); +} +/** Get Free Fall detection counter decrement configuration. + * Detection is registered by the Free Fall detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring FF_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * 
+ * + * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Free Fall detection, + * please refer to Registers 29 to 32. + * + * @return Current decrement configuration + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_FF_COUNT_BIT + */ +uint8_t MPU6050::getFreefallDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_FF_COUNT_BIT + */ +void MPU6050::setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement); +} +/** Get Motion detection counter decrement configuration. + * Detection is registered by the Motion detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring MOT_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * 
+ * + * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Motion detection, + * please refer to Registers 29 to 32. + * + */ +uint8_t MPU6050::getMotionDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_MOT_COUNT_BIT + */ +void MPU6050::setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement); +} + +// USER_CTRL register + +/** Get FIFO enabled status. + * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer + * cannot be written to or read from while disabled. The FIFO buffer's state + * does not change unless the MPU-60X0 is power cycled. + * @return Current FIFO enabled status + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_EN_BIT + */ +bool MPU6050::getFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_EN_BIT + */ +void MPU6050::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled); +} +/** Get I2C Master Mode enabled status. + * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the + * external sensor slave devices on the auxiliary I2C bus. When this bit is + * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically + * driven by the primary I2C bus (SDA and SCL). This is a precondition to + * enabling Bypass Mode. For further information regarding Bypass Mode, please + * refer to Register 55. + * @return Current I2C Master Mode enabled status + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_EN_BIT + */ +bool MPU6050::getI2CMasterModeEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_EN_BIT + */ +void MPU6050::setI2CMasterModeEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled); +} +/** Switch from I2C to SPI mode (MPU-6000 only) + * If this is set, the primary SPI interface will be enabled in place of the + * disabled primary I2C interface. + */ +void MPU6050::switchSPIEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This + * bit automatically clears to 0 after the reset has been triggered. + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_RESET_BIT + */ +void MPU6050::resetFIFO() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true); +} +/** Reset the I2C Master. + * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0. + * This bit automatically clears to 0 after the reset has been triggered. + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT + */ +void MPU6050::resetI2CMaster() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true); +} +/** Reset all sensor registers and signal paths. + * When set to 1, this bit resets the signal paths for all sensors (gyroscopes, + * accelerometers, and temperature sensor). This operation will also clear the + * sensor registers. This bit automatically clears to 0 after the reset has been + * triggered. + * + * When resetting only the signal path (and not the sensor registers), please + * use Register 104, SIGNAL_PATH_RESET. + * + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT + */ +void MPU6050::resetSensors() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true); +} + +// PWR_MGMT_1 register + +/** Trigger a full device reset. + * A small delay of ~50ms may be desirable after triggering a reset. + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_DEVICE_RESET_BIT + */ +void MPU6050::reset() { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true); +} +/** Get sleep mode status. + * Setting the SLEEP bit in the register puts the device into very low power + * sleep mode. In this mode, only the serial interface and internal registers + * remain active, allowing for a very low standby current. Clearing this bit + * puts the device back into normal mode. To save power, the individual standby + * selections for each of the gyros should be used if any gyro axis is not used + * by the application. + * @return Current sleep mode enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_SLEEP_BIT + */ +bool MPU6050::getSleepEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_SLEEP_BIT + */ +void MPU6050::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled); +} +/** Get wake cycle enabled status. + * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle + * between sleep mode and waking up to take a single sample of data from active + * sensors at a rate determined by LP_WAKE_CTRL (register 108). + * @return Current sleep mode enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CYCLE_BIT + */ +bool MPU6050::getWakeCycleEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer); + return buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CYCLE_BIT + */ +void MPU6050::setWakeCycleEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled); +} +/** Get temperature sensor enabled status. + * Control the usage of the internal temperature sensor. + * + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @return Current temperature sensor enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_TEMP_DIS_BIT + */ +bool MPU6050::getTempSensorEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer); + return buffer[0] == 0; // 1 is actually disabled here +} +/** Set temperature sensor enabled status. + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @param enabled New temperature sensor enabled status + * @see getTempSensorEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_TEMP_DIS_BIT + */ +void MPU6050::setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CLKSEL_BIT + * @see MPU6050_PWR1_CLKSEL_LENGTH + */ +uint8_t MPU6050::getClockSource() { + I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * An internal 8MHz oscillator, gyroscope based clock, or external sources can + * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator + * or an external source is chosen as the clock source, the MPU-60X0 can operate + * in low power modes with the gyroscopes disabled. + * + * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. + * However, it is highly recommended that the device be configured to use one of + * the gyroscopes (or an external clock source) as the clock reference for + * improved stability. The clock source can be selected according to the following table: + * + *
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * 
+ * + * @param source New clock source setting + * @see getClockSource() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CLKSEL_BIT + * @see MPU6050_PWR1_CLKSEL_LENGTH + */ +void MPU6050::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source); +} + +// PWR_MGMT_2 register + +/** Get wake frequency in Accel-Only Low Power Mode. + * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting + * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode, + * the device will power off all devices except for the primary I2C interface, + * waking only the accelerometer at fixed intervals to take a single + * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL + * as shown below: + * + *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * 
+ * + * For further information regarding the MPU-60X0's power modes, please refer to + * Register 107. + * + * @return Current wake frequency + * @see MPU6050_RA_PWR_MGMT_2 + */ +uint8_t MPU6050::getWakeFrequency() { + I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer); + return buffer[0]; +} +/** Set wake frequency in Accel-Only Low Power Mode. + * @param frequency New wake frequency + * @see MPU6050_RA_PWR_MGMT_2 + */ +void MPU6050::setWakeFrequency(uint8_t frequency) { + I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency); +} + +/** Get X-axis accelerometer standby enabled status. + * If enabled, the X-axis will not gather or report data (or use power). + * @return Current X-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XA_BIT + */ +bool MPU6050::getStandbyXAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer); + return buffer[0]; +} +/** Set X-axis accelerometer standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XA_BIT + */ +void MPU6050::setStandbyXAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled); +} +/** Get Y-axis accelerometer standby enabled status. + * If enabled, the Y-axis will not gather or report data (or use power). + * @return Current Y-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YA_BIT + */ +bool MPU6050::getStandbyYAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis accelerometer standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YA_BIT + */ +void MPU6050::setStandbyYAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled); +} +/** Get Z-axis accelerometer standby enabled status. + * If enabled, the Z-axis will not gather or report data (or use power). + * @return Current Z-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZA_BIT + */ +bool MPU6050::getStandbyZAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis accelerometer standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZA_BIT + */ +void MPU6050::setStandbyZAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled); +} +/** Get X-axis gyroscope standby enabled status. + * If enabled, the X-axis will not gather or report data (or use power). + * @return Current X-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XG_BIT + */ +bool MPU6050::getStandbyXGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer); + return buffer[0]; +} +/** Set X-axis gyroscope standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XG_BIT + */ +void MPU6050::setStandbyXGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled); +} +/** Get Y-axis gyroscope standby enabled status. + * If enabled, the Y-axis will not gather or report data (or use power). + * @return Current Y-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YG_BIT + */ +bool MPU6050::getStandbyYGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis gyroscope standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YG_BIT + */ +void MPU6050::setStandbyYGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled); +} +/** Get Z-axis gyroscope standby enabled status. + * If enabled, the Z-axis will not gather or report data (or use power). + * @return Current Z-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZG_BIT + */ +bool MPU6050::getStandbyZGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis gyroscope standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZG_BIT + */ +void MPU6050::setStandbyZGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled); +} + +// FIFO_COUNT* registers + +/** Get current FIFO buffer size. + * This value indicates the number of bytes stored in the FIFO buffer. This + * number is in turn the number of bytes that can be read from the FIFO buffer + * and it is directly proportional to the number of samples available given the + * set of sensor data bound to be stored in the FIFO (register 35 and 36). + * @return Current FIFO buffer size + */ +uint16_t MPU6050::getFIFOCount() { + I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} + +// FIFO_R_W register + +/** Get byte from FIFO buffer. + * This register is used to read and write data from the FIFO buffer. Data is + * written to the FIFO in order of register number (from lowest to highest). If + * all the FIFO enable flags (see below) are enabled and all External Sensor + * Data registers (Registers 73 to 96) are associated with a Slave device, the + * contents of registers 59 through 96 will be written in order at the Sample + * Rate. + * + * The contents of the sensor data registers (Registers 59 to 96) are written + * into the FIFO buffer when their corresponding FIFO enable flags are set to 1 + * in FIFO_EN (Register 35). An additional flag for the sensor data registers + * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36). + * + * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is + * automatically set to 1. This bit is located in INT_STATUS (Register 58). + * When the FIFO buffer has overflowed, the oldest data will be lost and new + * data will be written to the FIFO. + * + * If the FIFO buffer is empty, reading this register will return the last byte + * that was previously read from the FIFO until new data is available. The user + * should check FIFO_COUNT to ensure that the FIFO buffer is not read when + * empty. + * + * @return Byte from FIFO buffer + */ +uint8_t MPU6050::getFIFOByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer); + return buffer[0]; +} +void MPU6050::getFIFOBytes(uint8_t *data, uint8_t length) { + if(length > 0){ + I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data); + } else { + *data = 0; + } +} +/** Write byte to FIFO buffer. + * @see getFIFOByte() + * @see MPU6050_RA_FIFO_R_W + */ +void MPU6050::setFIFOByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FIFO_R_W, data); +} + +// WHO_AM_I register + +/** Get Device ID. + * This register is used to verify the identity of the device (0b110100, 0x34). + * @return Device ID (6 bits only! should be 0x34) + * @see MPU6050_RA_WHO_AM_I + * @see MPU6050_WHO_AM_I_BIT + * @see MPU6050_WHO_AM_I_LENGTH + */ +uint8_t MPU6050::getDeviceID() { + I2Cdev::readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer); + return buffer[0]; +} +/** Set Device ID. + * Write a new ID into the WHO_AM_I register (no idea why this should ever be + * necessary though). + * @param id New device ID to set. + * @see getDeviceID() + * @see MPU6050_RA_WHO_AM_I + * @see MPU6050_WHO_AM_I_BIT + * @see MPU6050_WHO_AM_I_LENGTH + */ +void MPU6050::setDeviceID(uint8_t id) { + I2Cdev::writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id); +} + +// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== + +// XG_OFFS_TC register + +uint8_t MPU6050::getOTPBankValid() { + I2Cdev::readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer); + return buffer[0]; +} +void MPU6050::setOTPBankValid(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled); +} +int8_t MPU6050::getXGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setXGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// YG_OFFS_TC register + +int8_t MPU6050::getYGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setYGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// ZG_OFFS_TC register + +int8_t MPU6050::getZGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setZGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// X_FINE_GAIN register + +int8_t MPU6050::getXFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setXFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain); +} + +// Y_FINE_GAIN register + +int8_t MPU6050::getYFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setYFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain); +} + +// Z_FINE_GAIN register + +int8_t MPU6050::getZFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setZFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain); +} + +// XA_OFFS_* registers + +int16_t MPU6050::getXAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setXAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset); +} + +// YA_OFFS_* register + +int16_t MPU6050::getYAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setYAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset); +} + +// ZA_OFFS_* register + +int16_t MPU6050::getZAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setZAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset); +} + +// XG_OFFS_USR* registers + +int16_t MPU6050::getXGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setXGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset); +} + +// YG_OFFS_USR* register + +int16_t MPU6050::getYGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setYGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset); +} + +// ZG_OFFS_USR* register + +int16_t MPU6050::getZGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setZGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset); +} + +// INT_ENABLE register (DMP functions) + +bool MPU6050::getIntPLLReadyEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer); + return buffer[0]; +} +void MPU6050::setIntPLLReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled); +} +bool MPU6050::getIntDMPEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer); + return buffer[0]; +} +void MPU6050::setIntDMPEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled); +} + +// DMP_INT_STATUS + +bool MPU6050::getDMPInt5Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt4Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt3Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt2Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt1Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt0Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer); + return buffer[0]; +} + +// INT_STATUS register (DMP functions) + +bool MPU6050::getIntPLLReadyStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getIntDMPStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer); + return buffer[0]; +} + +// USER_CTRL register (DMP functions) + +bool MPU6050::getDMPEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer); + return buffer[0]; +} +void MPU6050::setDMPEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled); +} +void MPU6050::resetDMP() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true); +} + +// BANK_SEL register + +void MPU6050::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) { + bank &= 0x1F; + if (userBank) bank |= 0x20; + if (prefetchEnabled) bank |= 0x40; + I2Cdev::writeByte(devAddr, MPU6050_RA_BANK_SEL, bank); +} + +// MEM_START_ADDR register + +void MPU6050::setMemoryStartAddress(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address); +} + +// MEM_R_W register + +uint8_t MPU6050::readMemoryByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_MEM_R_W, buffer); + return buffer[0]; +} +void MPU6050::writeMemoryByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_R_W, data); +} +void MPU6050::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) { + setMemoryBank(bank); + setMemoryStartAddress(address); + uint8_t chunkSize; + for (uint16_t i = 0; i < dataSize;) { + // determine correct chunk size according to bank position and data size + chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE; + + // make sure we don't go past the data size + if (i + chunkSize > dataSize) chunkSize = dataSize - i; + + // make sure this chunk doesn't go past the bank boundary (256 bytes) + if (chunkSize > 256 - address) chunkSize = 256 - address; + + // read the chunk of data as specified + I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i); + + // increase byte index by [chunkSize] + i += chunkSize; + + // uint8_t automatically wraps to 0 at 256 + address += chunkSize; + + // if we aren't done, update bank (if necessary) and address + if (i < dataSize) { + if (address == 0) bank++; + setMemoryBank(bank); + setMemoryStartAddress(address); + } + } +} +bool MPU6050::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) { + setMemoryBank(bank); + setMemoryStartAddress(address); + uint8_t chunkSize; + uint8_t *verifyBuffer=0; + uint8_t *progBuffer=0; + uint16_t i; + uint8_t j; + if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE); + if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE); + for (i = 0; i < dataSize;) { + // determine correct chunk size according to bank position and data size + chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE; + + // make sure we don't go past the data size + if (i + chunkSize > dataSize) chunkSize = dataSize - i; + + // make sure this chunk doesn't go past the bank boundary (256 bytes) + if (chunkSize > 256 - address) chunkSize = 256 - address; + + if (useProgMem) { + // write the chunk of data as specified + for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j); + } else { + // write the chunk of data as specified + progBuffer = (uint8_t *)data + i; + } + + I2Cdev::writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer); + + // verify data if needed + if (verify && verifyBuffer) { + setMemoryBank(bank); + setMemoryStartAddress(address); + I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer); + if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) { + /*Serial.print("Block write verification error, bank "); + Serial.print(bank, DEC); + Serial.print(", address "); + Serial.print(address, DEC); + Serial.print("!\nExpected:"); + for (j = 0; j < chunkSize; j++) { + Serial.print(" 0x"); + if (progBuffer[j] < 16) Serial.print("0"); + Serial.print(progBuffer[j], HEX); + } + Serial.print("\nReceived:"); + for (uint8_t j = 0; j < chunkSize; j++) { + Serial.print(" 0x"); + if (verifyBuffer[i + j] < 16) Serial.print("0"); + Serial.print(verifyBuffer[i + j], HEX); + } + Serial.print("\n");*/ + free(verifyBuffer); + if (useProgMem) free(progBuffer); + return false; // uh oh. + } + } + + // increase byte index by [chunkSize] + i += chunkSize; + + // uint8_t automatically wraps to 0 at 256 + address += chunkSize; + + // if we aren't done, update bank (if necessary) and address + if (i < dataSize) { + if (address == 0) bank++; + setMemoryBank(bank); + setMemoryStartAddress(address); + } + } + if (verify) free(verifyBuffer); + if (useProgMem) free(progBuffer); + return true; +} +bool MPU6050::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) { + return writeMemoryBlock(data, dataSize, bank, address, verify, true); +} +bool MPU6050::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) { + uint8_t *progBuffer = 0; + uint8_t success, special; + uint16_t i, j; + if (useProgMem) { + progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary + } + + // config set data is a long string of blocks with the following structure: + // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]] + uint8_t bank, offset, length; + for (i = 0; i < dataSize;) { + if (useProgMem) { + bank = pgm_read_byte(data + i++); + offset = pgm_read_byte(data + i++); + length = pgm_read_byte(data + i++); + } else { + bank = data[i++]; + offset = data[i++]; + length = data[i++]; + } + + // write data or perform special action + if (length > 0) { + // regular block of data to write + /*Serial.print("Writing config block to bank "); + Serial.print(bank); + Serial.print(", offset "); + Serial.print(offset); + Serial.print(", length="); + Serial.println(length);*/ + if (useProgMem) { + if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length); + for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j); + } else { + progBuffer = (uint8_t *)data + i; + } + success = writeMemoryBlock(progBuffer, length, bank, offset, true); + i += length; + } else { + // special instruction + // NOTE: this kind of behavior (what and when to do certain things) + // is totally undocumented. This code is in here based on observed + // behavior only, and exactly why (or even whether) it has to be here + // is anybody's guess for now. + if (useProgMem) { + special = pgm_read_byte(data + i++); + } else { + special = data[i++]; + } + /*Serial.print("Special command code "); + Serial.print(special, HEX); + Serial.println(" found...");*/ + if (special == 0x01) { + // enable DMP-related interrupts + + //setIntZeroMotionEnabled(true); + //setIntFIFOBufferOverflowEnabled(true); + //setIntDMPEnabled(true); + I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32); // single operation + + success = true; + } else { + // unknown special command + success = false; + } + } + + if (!success) { + if (useProgMem) free(progBuffer); + return false; // uh oh + } + } + if (useProgMem) free(progBuffer); + return true; +} +bool MPU6050::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) { + return writeDMPConfigurationSet(data, dataSize, true); +} + +// DMP_CFG_1 register + +uint8_t MPU6050::getDMPConfig1() { + I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer); + return buffer[0]; +} +void MPU6050::setDMPConfig1(uint8_t config) { + I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config); +} + +// DMP_CFG_2 register + +uint8_t MPU6050::getDMPConfig2() { + I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer); + return buffer[0]; +} +void MPU6050::setDMPConfig2(uint8_t config) { + I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config); +} diff --git a/firmware/lib/imu/MPU6050.h b/firmware/lib/imu/MPU6050.h new file mode 100644 index 0000000..6e3b9a7 --- /dev/null +++ b/firmware/lib/imu/MPU6050.h @@ -0,0 +1,1032 @@ +// 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 +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#ifndef _MPU6050_H_ +#define _MPU6050_H_ + +#include "I2Cdev.h" + +// supporting link: http://forum.arduino.cc/index.php?&topic=143444.msg1079517#msg1079517 +// also: http://forum.arduino.cc/index.php?&topic=141571.msg1062899#msg1062899s + +#ifdef __AVR__ +#include +#else +//#define PROGMEM /* empty */ +//#define pgm_read_byte(x) (*(x)) +//#define pgm_read_word(x) (*(x)) +//#define pgm_read_float(x) (*(x)) +//#define PSTR(STR) STR +#endif + + +#define MPU6050_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for InvenSense evaluation board +#define MPU6050_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC) +#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_SELF_TEST_X 0x0D //[7:5] XA_TEST[4-2], [4:0] XG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_Y 0x0E //[7:5] YA_TEST[4-2], [4:0] YG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_Z 0x0F //[7:5] ZA_TEST[4-2], [4:0] ZG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_A 0x10 //[5:4] XA_TEST[1-0], [3:2] YA_TEST[1-0], [1:0] ZA_TEST[1-0] +#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_SELF_TEST_XA_1_BIT 0x07 +#define MPU6050_SELF_TEST_XA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_XA_2_BIT 0x05 +#define MPU6050_SELF_TEST_XA_2_LENGTH 0x02 +#define MPU6050_SELF_TEST_YA_1_BIT 0x07 +#define MPU6050_SELF_TEST_YA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_YA_2_BIT 0x03 +#define MPU6050_SELF_TEST_YA_2_LENGTH 0x02 +#define MPU6050_SELF_TEST_ZA_1_BIT 0x07 +#define MPU6050_SELF_TEST_ZA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_ZA_2_BIT 0x01 +#define MPU6050_SELF_TEST_ZA_2_LENGTH 0x02 + +#define MPU6050_SELF_TEST_XG_1_BIT 0x04 +#define MPU6050_SELF_TEST_XG_1_LENGTH 0x05 +#define MPU6050_SELF_TEST_YG_1_BIT 0x04 +#define MPU6050_SELF_TEST_YG_1_LENGTH 0x05 +#define MPU6050_SELF_TEST_ZG_1_BIT 0x04 +#define MPU6050_SELF_TEST_ZG_1_LENGTH 0x05 + +#define MPU6050_TC_PWR_MODE_BIT 7 +#define MPU6050_TC_OFFSET_BIT 6 +#define MPU6050_TC_OFFSET_LENGTH 6 +#define MPU6050_TC_OTP_BNK_VLD_BIT 0 + +#define MPU6050_VDDIO_LEVEL_VLOGIC 0 +#define MPU6050_VDDIO_LEVEL_VDD 1 + +#define MPU6050_CFG_EXT_SYNC_SET_BIT 5 +#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3 +#define MPU6050_CFG_DLPF_CFG_BIT 2 +#define MPU6050_CFG_DLPF_CFG_LENGTH 3 + +#define MPU6050_EXT_SYNC_DISABLED 0x0 +#define MPU6050_EXT_SYNC_TEMP_OUT_L 0x1 +#define MPU6050_EXT_SYNC_GYRO_XOUT_L 0x2 +#define MPU6050_EXT_SYNC_GYRO_YOUT_L 0x3 +#define MPU6050_EXT_SYNC_GYRO_ZOUT_L 0x4 +#define MPU6050_EXT_SYNC_ACCEL_XOUT_L 0x5 +#define MPU6050_EXT_SYNC_ACCEL_YOUT_L 0x6 +#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L 0x7 + +#define MPU6050_DLPF_BW_256 0x00 +#define MPU6050_DLPF_BW_188 0x01 +#define MPU6050_DLPF_BW_98 0x02 +#define MPU6050_DLPF_BW_42 0x03 +#define MPU6050_DLPF_BW_20 0x04 +#define MPU6050_DLPF_BW_10 0x05 +#define MPU6050_DLPF_BW_5 0x06 + +#define MPU6050_GCONFIG_FS_SEL_BIT 4 +#define MPU6050_GCONFIG_FS_SEL_LENGTH 2 + +#define MPU6050_GYRO_FS_250 0x00 +#define MPU6050_GYRO_FS_500 0x01 +#define MPU6050_GYRO_FS_1000 0x02 +#define MPU6050_GYRO_FS_2000 0x03 + +#define MPU6050_ACONFIG_XA_ST_BIT 7 +#define MPU6050_ACONFIG_YA_ST_BIT 6 +#define MPU6050_ACONFIG_ZA_ST_BIT 5 +#define MPU6050_ACONFIG_AFS_SEL_BIT 4 +#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2 +#define MPU6050_ACONFIG_ACCEL_HPF_BIT 2 +#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH 3 + +#define MPU6050_ACCEL_FS_2 0x00 +#define MPU6050_ACCEL_FS_4 0x01 +#define MPU6050_ACCEL_FS_8 0x02 +#define MPU6050_ACCEL_FS_16 0x03 + +#define MPU6050_DHPF_RESET 0x00 +#define MPU6050_DHPF_5 0x01 +#define MPU6050_DHPF_2P5 0x02 +#define MPU6050_DHPF_1P25 0x03 +#define MPU6050_DHPF_0P63 0x04 +#define MPU6050_DHPF_HOLD 0x07 + +#define MPU6050_TEMP_FIFO_EN_BIT 7 +#define MPU6050_XG_FIFO_EN_BIT 6 +#define MPU6050_YG_FIFO_EN_BIT 5 +#define MPU6050_ZG_FIFO_EN_BIT 4 +#define MPU6050_ACCEL_FIFO_EN_BIT 3 +#define MPU6050_SLV2_FIFO_EN_BIT 2 +#define MPU6050_SLV1_FIFO_EN_BIT 1 +#define MPU6050_SLV0_FIFO_EN_BIT 0 + +#define MPU6050_MULT_MST_EN_BIT 7 +#define MPU6050_WAIT_FOR_ES_BIT 6 +#define MPU6050_SLV_3_FIFO_EN_BIT 5 +#define MPU6050_I2C_MST_P_NSR_BIT 4 +#define MPU6050_I2C_MST_CLK_BIT 3 +#define MPU6050_I2C_MST_CLK_LENGTH 4 + +#define MPU6050_CLOCK_DIV_348 0x0 +#define MPU6050_CLOCK_DIV_333 0x1 +#define MPU6050_CLOCK_DIV_320 0x2 +#define MPU6050_CLOCK_DIV_308 0x3 +#define MPU6050_CLOCK_DIV_296 0x4 +#define MPU6050_CLOCK_DIV_286 0x5 +#define MPU6050_CLOCK_DIV_276 0x6 +#define MPU6050_CLOCK_DIV_267 0x7 +#define MPU6050_CLOCK_DIV_258 0x8 +#define MPU6050_CLOCK_DIV_500 0x9 +#define MPU6050_CLOCK_DIV_471 0xA +#define MPU6050_CLOCK_DIV_444 0xB +#define MPU6050_CLOCK_DIV_421 0xC +#define MPU6050_CLOCK_DIV_400 0xD +#define MPU6050_CLOCK_DIV_381 0xE +#define MPU6050_CLOCK_DIV_364 0xF + +#define MPU6050_I2C_SLV_RW_BIT 7 +#define MPU6050_I2C_SLV_ADDR_BIT 6 +#define MPU6050_I2C_SLV_ADDR_LENGTH 7 +#define MPU6050_I2C_SLV_EN_BIT 7 +#define MPU6050_I2C_SLV_BYTE_SW_BIT 6 +#define MPU6050_I2C_SLV_REG_DIS_BIT 5 +#define MPU6050_I2C_SLV_GRP_BIT 4 +#define MPU6050_I2C_SLV_LEN_BIT 3 +#define MPU6050_I2C_SLV_LEN_LENGTH 4 + +#define MPU6050_I2C_SLV4_RW_BIT 7 +#define MPU6050_I2C_SLV4_ADDR_BIT 6 +#define MPU6050_I2C_SLV4_ADDR_LENGTH 7 +#define MPU6050_I2C_SLV4_EN_BIT 7 +#define MPU6050_I2C_SLV4_INT_EN_BIT 6 +#define MPU6050_I2C_SLV4_REG_DIS_BIT 5 +#define MPU6050_I2C_SLV4_MST_DLY_BIT 4 +#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5 + +#define MPU6050_MST_PASS_THROUGH_BIT 7 +#define MPU6050_MST_I2C_SLV4_DONE_BIT 6 +#define MPU6050_MST_I2C_LOST_ARB_BIT 5 +#define MPU6050_MST_I2C_SLV4_NACK_BIT 4 +#define MPU6050_MST_I2C_SLV3_NACK_BIT 3 +#define MPU6050_MST_I2C_SLV2_NACK_BIT 2 +#define MPU6050_MST_I2C_SLV1_NACK_BIT 1 +#define MPU6050_MST_I2C_SLV0_NACK_BIT 0 + +#define MPU6050_INTCFG_INT_LEVEL_BIT 7 +#define MPU6050_INTCFG_INT_OPEN_BIT 6 +#define MPU6050_INTCFG_LATCH_INT_EN_BIT 5 +#define MPU6050_INTCFG_INT_RD_CLEAR_BIT 4 +#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT 3 +#define MPU6050_INTCFG_FSYNC_INT_EN_BIT 2 +#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT 1 +#define MPU6050_INTCFG_CLKOUT_EN_BIT 0 + +#define MPU6050_INTMODE_ACTIVEHIGH 0x00 +#define MPU6050_INTMODE_ACTIVELOW 0x01 + +#define MPU6050_INTDRV_PUSHPULL 0x00 +#define MPU6050_INTDRV_OPENDRAIN 0x01 + +#define MPU6050_INTLATCH_50USPULSE 0x00 +#define MPU6050_INTLATCH_WAITCLEAR 0x01 + +#define MPU6050_INTCLEAR_STATUSREAD 0x00 +#define MPU6050_INTCLEAR_ANYREAD 0x01 + +#define MPU6050_INTERRUPT_FF_BIT 7 +#define MPU6050_INTERRUPT_MOT_BIT 6 +#define MPU6050_INTERRUPT_ZMOT_BIT 5 +#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT 4 +#define MPU6050_INTERRUPT_I2C_MST_INT_BIT 3 +#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT 2 +#define MPU6050_INTERRUPT_DMP_INT_BIT 1 +#define MPU6050_INTERRUPT_DATA_RDY_BIT 0 + +// TODO: figure out what these actually do +// UMPL source code is not very obivous +#define MPU6050_DMPINT_5_BIT 5 +#define MPU6050_DMPINT_4_BIT 4 +#define MPU6050_DMPINT_3_BIT 3 +#define MPU6050_DMPINT_2_BIT 2 +#define MPU6050_DMPINT_1_BIT 1 +#define MPU6050_DMPINT_0_BIT 0 + +#define MPU6050_MOTION_MOT_XNEG_BIT 7 +#define MPU6050_MOTION_MOT_XPOS_BIT 6 +#define MPU6050_MOTION_MOT_YNEG_BIT 5 +#define MPU6050_MOTION_MOT_YPOS_BIT 4 +#define MPU6050_MOTION_MOT_ZNEG_BIT 3 +#define MPU6050_MOTION_MOT_ZPOS_BIT 2 +#define MPU6050_MOTION_MOT_ZRMOT_BIT 0 + +#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT 7 +#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4 +#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3 +#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2 +#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1 +#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0 + +#define MPU6050_PATHRESET_GYRO_RESET_BIT 2 +#define MPU6050_PATHRESET_ACCEL_RESET_BIT 1 +#define MPU6050_PATHRESET_TEMP_RESET_BIT 0 + +#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT 5 +#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH 2 +#define MPU6050_DETECT_FF_COUNT_BIT 3 +#define MPU6050_DETECT_FF_COUNT_LENGTH 2 +#define MPU6050_DETECT_MOT_COUNT_BIT 1 +#define MPU6050_DETECT_MOT_COUNT_LENGTH 2 + +#define MPU6050_DETECT_DECREMENT_RESET 0x0 +#define MPU6050_DETECT_DECREMENT_1 0x1 +#define MPU6050_DETECT_DECREMENT_2 0x2 +#define MPU6050_DETECT_DECREMENT_4 0x3 + +#define MPU6050_USERCTRL_DMP_EN_BIT 7 +#define MPU6050_USERCTRL_FIFO_EN_BIT 6 +#define MPU6050_USERCTRL_I2C_MST_EN_BIT 5 +#define MPU6050_USERCTRL_I2C_IF_DIS_BIT 4 +#define MPU6050_USERCTRL_DMP_RESET_BIT 3 +#define MPU6050_USERCTRL_FIFO_RESET_BIT 2 +#define MPU6050_USERCTRL_I2C_MST_RESET_BIT 1 +#define MPU6050_USERCTRL_SIG_COND_RESET_BIT 0 + +#define MPU6050_PWR1_DEVICE_RESET_BIT 7 +#define MPU6050_PWR1_SLEEP_BIT 6 +#define MPU6050_PWR1_CYCLE_BIT 5 +#define MPU6050_PWR1_TEMP_DIS_BIT 3 +#define MPU6050_PWR1_CLKSEL_BIT 2 +#define MPU6050_PWR1_CLKSEL_LENGTH 3 + +#define MPU6050_CLOCK_INTERNAL 0x00 +#define MPU6050_CLOCK_PLL_XGYRO 0x01 +#define MPU6050_CLOCK_PLL_YGYRO 0x02 +#define MPU6050_CLOCK_PLL_ZGYRO 0x03 +#define MPU6050_CLOCK_PLL_EXT32K 0x04 +#define MPU6050_CLOCK_PLL_EXT19M 0x05 +#define MPU6050_CLOCK_KEEP_RESET 0x07 + +#define MPU6050_PWR2_LP_WAKE_CTRL_BIT 7 +#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH 2 +#define MPU6050_PWR2_STBY_XA_BIT 5 +#define MPU6050_PWR2_STBY_YA_BIT 4 +#define MPU6050_PWR2_STBY_ZA_BIT 3 +#define MPU6050_PWR2_STBY_XG_BIT 2 +#define MPU6050_PWR2_STBY_YG_BIT 1 +#define MPU6050_PWR2_STBY_ZG_BIT 0 + +#define MPU6050_WAKE_FREQ_1P25 0x0 +#define MPU6050_WAKE_FREQ_2P5 0x1 +#define MPU6050_WAKE_FREQ_5 0x2 +#define MPU6050_WAKE_FREQ_10 0x3 + +#define MPU6050_BANKSEL_PRFTCH_EN_BIT 6 +#define MPU6050_BANKSEL_CFG_USER_BANK_BIT 5 +#define MPU6050_BANKSEL_MEM_SEL_BIT 4 +#define MPU6050_BANKSEL_MEM_SEL_LENGTH 5 + +#define MPU6050_WHO_AM_I_BIT 6 +#define MPU6050_WHO_AM_I_LENGTH 6 + +#define MPU6050_DMP_MEMORY_BANKS 8 +#define MPU6050_DMP_MEMORY_BANK_SIZE 256 +#define MPU6050_DMP_MEMORY_CHUNK_SIZE 16 + +// note: DMP code memory blocks defined at end of header file + +class MPU6050 { + public: + MPU6050(); + MPU6050(uint8_t address); + + void initialize(); + bool testConnection(); + + // AUX_VDDIO register + uint8_t getAuxVDDIOLevel(); + void setAuxVDDIOLevel(uint8_t level); + + // SMPLRT_DIV register + uint8_t getRate(); + void setRate(uint8_t rate); + + // CONFIG register + uint8_t getExternalFrameSync(); + void setExternalFrameSync(uint8_t sync); + uint8_t getDLPFMode(); + void setDLPFMode(uint8_t bandwidth); + + // GYRO_CONFIG register + uint8_t getFullScaleGyroRange(); + void setFullScaleGyroRange(uint8_t range); + + // SELF_TEST registers + uint8_t getAccelXSelfTestFactoryTrim(); + uint8_t getAccelYSelfTestFactoryTrim(); + uint8_t getAccelZSelfTestFactoryTrim(); + + uint8_t getGyroXSelfTestFactoryTrim(); + uint8_t getGyroYSelfTestFactoryTrim(); + uint8_t getGyroZSelfTestFactoryTrim(); + + // ACCEL_CONFIG register + bool getAccelXSelfTest(); + void setAccelXSelfTest(bool enabled); + bool getAccelYSelfTest(); + void setAccelYSelfTest(bool enabled); + bool getAccelZSelfTest(); + void setAccelZSelfTest(bool enabled); + uint8_t getFullScaleAccelRange(); + void setFullScaleAccelRange(uint8_t range); + uint8_t getDHPFMode(); + void setDHPFMode(uint8_t mode); + + // FF_THR register + uint8_t getFreefallDetectionThreshold(); + void setFreefallDetectionThreshold(uint8_t threshold); + + // FF_DUR register + uint8_t getFreefallDetectionDuration(); + void setFreefallDetectionDuration(uint8_t duration); + + // MOT_THR register + uint8_t getMotionDetectionThreshold(); + void setMotionDetectionThreshold(uint8_t threshold); + + // MOT_DUR register + uint8_t getMotionDetectionDuration(); + void setMotionDetectionDuration(uint8_t duration); + + // ZRMOT_THR register + uint8_t getZeroMotionDetectionThreshold(); + void setZeroMotionDetectionThreshold(uint8_t threshold); + + // ZRMOT_DUR register + uint8_t getZeroMotionDetectionDuration(); + void setZeroMotionDetectionDuration(uint8_t duration); + + // FIFO_EN register + bool getTempFIFOEnabled(); + void setTempFIFOEnabled(bool enabled); + bool getXGyroFIFOEnabled(); + void setXGyroFIFOEnabled(bool enabled); + bool getYGyroFIFOEnabled(); + void setYGyroFIFOEnabled(bool enabled); + bool getZGyroFIFOEnabled(); + void setZGyroFIFOEnabled(bool enabled); + bool getAccelFIFOEnabled(); + void setAccelFIFOEnabled(bool enabled); + bool getSlave2FIFOEnabled(); + void setSlave2FIFOEnabled(bool enabled); + bool getSlave1FIFOEnabled(); + void setSlave1FIFOEnabled(bool enabled); + bool getSlave0FIFOEnabled(); + void setSlave0FIFOEnabled(bool enabled); + + // I2C_MST_CTRL register + bool getMultiMasterEnabled(); + void setMultiMasterEnabled(bool enabled); + bool getWaitForExternalSensorEnabled(); + void setWaitForExternalSensorEnabled(bool enabled); + bool getSlave3FIFOEnabled(); + void setSlave3FIFOEnabled(bool enabled); + bool getSlaveReadWriteTransitionEnabled(); + void setSlaveReadWriteTransitionEnabled(bool enabled); + uint8_t getMasterClockSpeed(); + void setMasterClockSpeed(uint8_t speed); + + // I2C_SLV* registers (Slave 0-3) + uint8_t getSlaveAddress(uint8_t num); + void setSlaveAddress(uint8_t num, uint8_t address); + uint8_t getSlaveRegister(uint8_t num); + void setSlaveRegister(uint8_t num, uint8_t reg); + bool getSlaveEnabled(uint8_t num); + void setSlaveEnabled(uint8_t num, bool enabled); + bool getSlaveWordByteSwap(uint8_t num); + void setSlaveWordByteSwap(uint8_t num, bool enabled); + bool getSlaveWriteMode(uint8_t num); + void setSlaveWriteMode(uint8_t num, bool mode); + bool getSlaveWordGroupOffset(uint8_t num); + void setSlaveWordGroupOffset(uint8_t num, bool enabled); + uint8_t getSlaveDataLength(uint8_t num); + void setSlaveDataLength(uint8_t num, uint8_t length); + + // I2C_SLV* registers (Slave 4) + uint8_t getSlave4Address(); + void setSlave4Address(uint8_t address); + uint8_t getSlave4Register(); + void setSlave4Register(uint8_t reg); + void setSlave4OutputByte(uint8_t data); + bool getSlave4Enabled(); + void setSlave4Enabled(bool enabled); + bool getSlave4InterruptEnabled(); + void setSlave4InterruptEnabled(bool enabled); + bool getSlave4WriteMode(); + void setSlave4WriteMode(bool mode); + uint8_t getSlave4MasterDelay(); + void setSlave4MasterDelay(uint8_t delay); + uint8_t getSlate4InputByte(); + + // I2C_MST_STATUS register + bool getPassthroughStatus(); + bool getSlave4IsDone(); + bool getLostArbitration(); + bool getSlave4Nack(); + bool getSlave3Nack(); + bool getSlave2Nack(); + bool getSlave1Nack(); + bool getSlave0Nack(); + + // INT_PIN_CFG register + bool getInterruptMode(); + void setInterruptMode(bool mode); + bool getInterruptDrive(); + void setInterruptDrive(bool drive); + bool getInterruptLatch(); + void setInterruptLatch(bool latch); + bool getInterruptLatchClear(); + void setInterruptLatchClear(bool clear); + bool getFSyncInterruptLevel(); + void setFSyncInterruptLevel(bool level); + bool getFSyncInterruptEnabled(); + void setFSyncInterruptEnabled(bool enabled); + bool getI2CBypassEnabled(); + void setI2CBypassEnabled(bool enabled); + bool getClockOutputEnabled(); + void setClockOutputEnabled(bool enabled); + + // INT_ENABLE register + uint8_t getIntEnabled(); + void setIntEnabled(uint8_t enabled); + bool getIntFreefallEnabled(); + void setIntFreefallEnabled(bool enabled); + bool getIntMotionEnabled(); + void setIntMotionEnabled(bool enabled); + bool getIntZeroMotionEnabled(); + void setIntZeroMotionEnabled(bool enabled); + bool getIntFIFOBufferOverflowEnabled(); + void setIntFIFOBufferOverflowEnabled(bool enabled); + bool getIntI2CMasterEnabled(); + void setIntI2CMasterEnabled(bool enabled); + bool getIntDataReadyEnabled(); + void setIntDataReadyEnabled(bool enabled); + + // INT_STATUS register + uint8_t getIntStatus(); + bool getIntFreefallStatus(); + bool getIntMotionStatus(); + bool getIntZeroMotionStatus(); + bool getIntFIFOBufferOverflowStatus(); + bool getIntI2CMasterStatus(); + bool getIntDataReadyStatus(); + + // ACCEL_*OUT_* registers + void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz); + void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz); + void getAcceleration(int16_t* x, int16_t* y, int16_t* z); + int16_t getAccelerationX(); + int16_t getAccelerationY(); + int16_t getAccelerationZ(); + + // TEMP_OUT_* registers + int16_t getTemperature(); + + // GYRO_*OUT_* registers + void getRotation(int16_t* x, int16_t* y, int16_t* z); + int16_t getRotationX(); + int16_t getRotationY(); + int16_t getRotationZ(); + + // EXT_SENS_DATA_* registers + uint8_t getExternalSensorByte(int position); + uint16_t getExternalSensorWord(int position); + uint32_t getExternalSensorDWord(int position); + + // MOT_DETECT_STATUS register + uint8_t getMotionStatus(); + bool getXNegMotionDetected(); + bool getXPosMotionDetected(); + bool getYNegMotionDetected(); + bool getYPosMotionDetected(); + bool getZNegMotionDetected(); + bool getZPosMotionDetected(); + bool getZeroMotionDetected(); + + // I2C_SLV*_DO register + void setSlaveOutputByte(uint8_t num, uint8_t data); + + // I2C_MST_DELAY_CTRL register + bool getExternalShadowDelayEnabled(); + void setExternalShadowDelayEnabled(bool enabled); + bool getSlaveDelayEnabled(uint8_t num); + void setSlaveDelayEnabled(uint8_t num, bool enabled); + + // SIGNAL_PATH_RESET register + void resetGyroscopePath(); + void resetAccelerometerPath(); + void resetTemperaturePath(); + + // MOT_DETECT_CTRL register + uint8_t getAccelerometerPowerOnDelay(); + void setAccelerometerPowerOnDelay(uint8_t delay); + uint8_t getFreefallDetectionCounterDecrement(); + void setFreefallDetectionCounterDecrement(uint8_t decrement); + uint8_t getMotionDetectionCounterDecrement(); + void setMotionDetectionCounterDecrement(uint8_t decrement); + + // USER_CTRL register + bool getFIFOEnabled(); + void setFIFOEnabled(bool enabled); + bool getI2CMasterModeEnabled(); + void setI2CMasterModeEnabled(bool enabled); + void switchSPIEnabled(bool enabled); + void resetFIFO(); + void resetI2CMaster(); + void resetSensors(); + + // PWR_MGMT_1 register + void reset(); + bool getSleepEnabled(); + void setSleepEnabled(bool enabled); + bool getWakeCycleEnabled(); + void setWakeCycleEnabled(bool enabled); + bool getTempSensorEnabled(); + void setTempSensorEnabled(bool enabled); + uint8_t getClockSource(); + void setClockSource(uint8_t source); + + // PWR_MGMT_2 register + uint8_t getWakeFrequency(); + void setWakeFrequency(uint8_t frequency); + bool getStandbyXAccelEnabled(); + void setStandbyXAccelEnabled(bool enabled); + bool getStandbyYAccelEnabled(); + void setStandbyYAccelEnabled(bool enabled); + bool getStandbyZAccelEnabled(); + void setStandbyZAccelEnabled(bool enabled); + bool getStandbyXGyroEnabled(); + void setStandbyXGyroEnabled(bool enabled); + bool getStandbyYGyroEnabled(); + void setStandbyYGyroEnabled(bool enabled); + bool getStandbyZGyroEnabled(); + void setStandbyZGyroEnabled(bool enabled); + + // FIFO_COUNT_* registers + uint16_t getFIFOCount(); + + // FIFO_R_W register + uint8_t getFIFOByte(); + void setFIFOByte(uint8_t data); + void getFIFOBytes(uint8_t *data, uint8_t length); + + // WHO_AM_I register + uint8_t getDeviceID(); + void setDeviceID(uint8_t id); + + // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== + + // XG_OFFS_TC register + uint8_t getOTPBankValid(); + void setOTPBankValid(bool enabled); + int8_t getXGyroOffsetTC(); + void setXGyroOffsetTC(int8_t offset); + + // YG_OFFS_TC register + int8_t getYGyroOffsetTC(); + void setYGyroOffsetTC(int8_t offset); + + // ZG_OFFS_TC register + int8_t getZGyroOffsetTC(); + void setZGyroOffsetTC(int8_t offset); + + // X_FINE_GAIN register + int8_t getXFineGain(); + void setXFineGain(int8_t gain); + + // Y_FINE_GAIN register + int8_t getYFineGain(); + void setYFineGain(int8_t gain); + + // Z_FINE_GAIN register + int8_t getZFineGain(); + void setZFineGain(int8_t gain); + + // XA_OFFS_* registers + int16_t getXAccelOffset(); + void setXAccelOffset(int16_t offset); + + // YA_OFFS_* register + int16_t getYAccelOffset(); + void setYAccelOffset(int16_t offset); + + // ZA_OFFS_* register + int16_t getZAccelOffset(); + void setZAccelOffset(int16_t offset); + + // XG_OFFS_USR* registers + int16_t getXGyroOffset(); + void setXGyroOffset(int16_t offset); + + // YG_OFFS_USR* register + int16_t getYGyroOffset(); + void setYGyroOffset(int16_t offset); + + // ZG_OFFS_USR* register + int16_t getZGyroOffset(); + void setZGyroOffset(int16_t offset); + + // INT_ENABLE register (DMP functions) + bool getIntPLLReadyEnabled(); + void setIntPLLReadyEnabled(bool enabled); + bool getIntDMPEnabled(); + void setIntDMPEnabled(bool enabled); + + // DMP_INT_STATUS + bool getDMPInt5Status(); + bool getDMPInt4Status(); + bool getDMPInt3Status(); + bool getDMPInt2Status(); + bool getDMPInt1Status(); + bool getDMPInt0Status(); + + // INT_STATUS register (DMP functions) + bool getIntPLLReadyStatus(); + bool getIntDMPStatus(); + + // USER_CTRL register (DMP functions) + bool getDMPEnabled(); + void setDMPEnabled(bool enabled); + void resetDMP(); + + // BANK_SEL register + void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false); + + // MEM_START_ADDR register + void setMemoryStartAddress(uint8_t address); + + // MEM_R_W register + uint8_t readMemoryByte(); + void writeMemoryByte(uint8_t data); + void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0); + bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false); + bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true); + + bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false); + bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize); + + // DMP_CFG_1 register + uint8_t getDMPConfig1(); + void setDMPConfig1(uint8_t config); + + // DMP_CFG_2 register + uint8_t getDMPConfig2(); + void setDMPConfig2(uint8_t config); + + // special methods for MotionApps 2.0 implementation + #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20 + uint8_t *dmpPacketBuffer; + uint16_t dmpPacketSize; + + uint8_t dmpInitialize(); + bool dmpPacketAvailable(); + + uint8_t dmpSetFIFORate(uint8_t fifoRate); + uint8_t dmpGetFIFORate(); + uint8_t dmpGetSampleStepSizeMS(); + uint8_t dmpGetSampleFrequency(); + int32_t dmpDecodeTemperature(int8_t tempReg); + + // Register callbacks after a packet of FIFO data is processed + //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); + //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func); + uint8_t dmpRunFIFORateProcesses(); + + // Setup FIFO for various output + uint8_t dmpSendQuaternion(uint_fast16_t accuracy); + uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendPacketNumber(uint_fast16_t accuracy); + uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + + // Get Fixed Point data from FIFO + uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpSetLinearAccelFilterCoefficient(float coef); + uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity); + uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q); + uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q); + uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0); + uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0); + + uint8_t dmpGetEuler(float *data, Quaternion *q); + uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity); + + // Get Floating Point data from FIFO + uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0); + + uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData); + uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL); + + uint8_t dmpSetFIFOProcessedCallback(void (*func) (void)); + + uint8_t dmpInitFIFOParam(); + uint8_t dmpCloseFIFO(); + uint8_t dmpSetGyroDataSource(uint8_t source); + uint8_t dmpDecodeQuantizedAccel(); + uint32_t dmpGetGyroSumOfSquare(); + uint32_t dmpGetAccelSumOfSquare(); + void dmpOverrideQuaternion(long *q); + uint16_t dmpGetFIFOPacketSize(); + #endif + + // special methods for MotionApps 4.1 implementation + #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS41 + uint8_t *dmpPacketBuffer; + uint16_t dmpPacketSize; + + uint8_t dmpInitialize(); + bool dmpPacketAvailable(); + + uint8_t dmpSetFIFORate(uint8_t fifoRate); + uint8_t dmpGetFIFORate(); + uint8_t dmpGetSampleStepSizeMS(); + uint8_t dmpGetSampleFrequency(); + int32_t dmpDecodeTemperature(int8_t tempReg); + + // Register callbacks after a packet of FIFO data is processed + //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); + //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func); + uint8_t dmpRunFIFORateProcesses(); + + // Setup FIFO for various output + uint8_t dmpSendQuaternion(uint_fast16_t accuracy); + uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendPacketNumber(uint_fast16_t accuracy); + uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + + // Get Fixed Point data from FIFO + uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0); + uint8_t dmpSetLinearAccelFilterCoefficient(float coef); + uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity); + uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q); + uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q); + uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0); + uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0); + + uint8_t dmpGetEuler(float *data, Quaternion *q); + uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity); + + // Get Floating Point data from FIFO + uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0); + + uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData); + uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL); + + uint8_t dmpSetFIFOProcessedCallback(void (*func) (void)); + + uint8_t dmpInitFIFOParam(); + uint8_t dmpCloseFIFO(); + uint8_t dmpSetGyroDataSource(uint8_t source); + uint8_t dmpDecodeQuantizedAccel(); + uint32_t dmpGetGyroSumOfSquare(); + uint32_t dmpGetAccelSumOfSquare(); + void dmpOverrideQuaternion(long *q); + uint16_t dmpGetFIFOPacketSize(); + #endif + + private: + uint8_t devAddr; + uint8_t buffer[14]; +}; + +#endif /* _MPU6050_H_ */ diff --git a/firmware/lib/imu/MPU9150.cpp b/firmware/lib/imu/MPU9150.cpp new file mode 100644 index 0000000..689a856 --- /dev/null +++ b/firmware/lib/imu/MPU9150.cpp @@ -0,0 +1,3167 @@ +// I2Cdev library collection - MPU9150 I2C device class +// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 8/24/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Jeff Rowberg + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in +all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +THE SOFTWARE. +=============================================== +*/ + +#include "MPU9150.h" + +/** Default constructor, uses default I2C address. + * @see MPU9150_DEFAULT_ADDRESS + */ +MPU9150::MPU9150() { + devAddr = MPU9150_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see MPU9150_DEFAULT_ADDRESS + * @see MPU9150_ADDRESS_AD0_LOW + * @see MPU9150_ADDRESS_AD0_HIGH + */ +MPU9150::MPU9150(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the device and take it out of sleep mode (which must be done + * after start-up). This function also sets both the accelerometer and the gyroscope + * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets + * the clock source to use the X Gyro for reference, which is slightly better than + * the default internal clock source. + */ +void MPU9150::initialize() { + setClockSource(MPU9150_CLOCK_PLL_XGYRO); + setFullScaleGyroRange(MPU9150_GYRO_FS_250); + setFullScaleAccelRange(MPU9150_ACCEL_FS_2); + setSleepEnabled(false); // thanks to Jack Elston for pointing this one out! +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool MPU9150::testConnection() { + return 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 MPU9150::getAuxVDDIOLevel() { + I2Cdev::readBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_PWR_MODE_BIT, buffer); + return buffer[0]; +} +/** Set the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @param level I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +void MPU9150::setAuxVDDIOLevel(uint8_t level) { + I2Cdev::writeBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_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-9150 Product Specification document. + * + * @return Current sample rate + * @see MPU9150_RA_SMPLRT_DIV + */ +uint8_t MPU9150::getRate() { + I2Cdev::readByte(devAddr, MPU9150_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set gyroscope sample rate divider. + * @param rate New sample rate divider + * @see getRate() + * @see MPU9150_RA_SMPLRT_DIV + */ +void MPU9150::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150::getExternalFrameSync() { + I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_CFG_EXT_SYNC_SET_LENGTH, buffer); + return buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see MPU9150_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void MPU9150::setExternalFrameSync(uint8_t sync) { + I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_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 MPU9150_RA_CONFIG + * @see MPU9150_CFG_DLPF_CFG_BIT + * @see MPU9150_CFG_DLPF_CFG_LENGTH + */ +uint8_t MPU9150::getDLPFMode() { + I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_CFG_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see MPU9150_DLPF_BW_256 + * @see MPU9150_RA_CONFIG + * @see MPU9150_CFG_DLPF_CFG_BIT + * @see MPU9150_CFG_DLPF_CFG_LENGTH + */ +void MPU9150::setDLPFMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_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 MPU9150_GYRO_FS_250 + * @see MPU9150_RA_GYRO_CONFIG + * @see MPU9150_GCONFIG_FS_SEL_BIT + * @see MPU9150_GCONFIG_FS_SEL_LENGTH + */ +uint8_t MPU9150::getFullScaleGyroRange() { + I2Cdev::readBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see MPU9150_GYRO_FS_250 + * @see MPU9150_RA_GYRO_CONFIG + * @see MPU9150_GCONFIG_FS_SEL_BIT + * @see MPU9150_GCONFIG_FS_SEL_LENGTH + */ +void MPU9150::setFullScaleGyroRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, range); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelXSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelXSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelYSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelYSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelZSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ZA_ST_BIT, buffer); + return buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelZSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_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 MPU9150_ACCEL_FS_2 + * @see MPU9150_RA_ACCEL_CONFIG + * @see MPU9150_ACONFIG_AFS_SEL_BIT + * @see MPU9150_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t MPU9150::getFullScaleAccelRange() { + I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_ACONFIG_AFS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void MPU9150::setFullScaleAccelRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_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-9150 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 MPU9150_DHPF_RESET + * @see MPU9150_RA_ACCEL_CONFIG + */ +uint8_t MPU9150::getDHPFMode() { + I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_ACONFIG_ACCEL_HPF_LENGTH, buffer); + return buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see MPU9150_DHPF_RESET + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setDHPFMode(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_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-9150 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current free-fall acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_FF_THR + */ +uint8_t MPU9150::getFreefallDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_FF_THR, buffer); + return buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see MPU9150_RA_FF_THR + */ +void MPU9150::setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_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-9150 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current free-fall duration threshold value (LSB = 1ms) + * @see MPU9150_RA_FF_DUR + */ +uint8_t MPU9150::getFreefallDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_FF_DUR, buffer); + return buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see MPU9150_RA_FF_DUR + */ +void MPU9150::setFreefallDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_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-9150 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_MOT_THR + */ +uint8_t MPU9150::getMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_MOT_THR, buffer); + return buffer[0]; +} +/** Set free-fall event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see MPU9150_RA_MOT_THR + */ +void MPU9150::setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_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-9150 Product Specification document. + * + * @return Current motion detection duration threshold value (LSB = 1ms) + * @see MPU9150_RA_MOT_DUR + */ +uint8_t MPU9150::getMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_MOT_DUR, buffer); + return buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see MPU9150_RA_MOT_DUR + */ +void MPU9150::setMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_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-9150 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_ZRMOT_THR + */ +uint8_t MPU9150::getZeroMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_THR, buffer); + return buffer[0]; +} +/** Set zero motion detection event acceleration threshold. + * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) + * @see getZeroMotionDetectionThreshold() + * @see MPU9150_RA_ZRMOT_THR + */ +void MPU9150::setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_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-9150 Product Specification document, as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection duration threshold value (LSB = 64ms) + * @see MPU9150_RA_ZRMOT_DUR + */ +uint8_t MPU9150::getZeroMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_DUR, buffer); + return buffer[0]; +} +/** Set zero motion detection event duration threshold. + * @param duration New zero motion detection duration threshold value (LSB = 1ms) + * @see getZeroMotionDetectionDuration() + * @see MPU9150_RA_ZRMOT_DUR + */ +void MPU9150::setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_RA_ZRMOT_DUR, duration); +} + +// FIFO_EN register + +/** Get temperature FIFO enabled value. + * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and + * 66) to be written into the FIFO buffer. + * @return Current temperature FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getTempFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setTempFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, enabled); +} +/** Get gyroscope X-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and + * 68) to be written into the FIFO buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getXGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setXGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Y-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and + * 70) to be written into the FIFO buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getYGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setYGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Z-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and + * 72) to be written into the FIFO buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getZGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setZGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, enabled); +} +/** Get accelerometer FIFO enabled value. + * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, + * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be + * written into the FIFO buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, enabled); +} +/** Get Slave 2 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 2 to be written into the FIFO buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave2FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave2FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, enabled); +} +/** Get Slave 1 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 1 to be written into the FIFO buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave1FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave1FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, enabled); +} +/** Get Slave 0 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 0 to be written into the FIFO buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave0FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV0_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave0FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_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 MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getMultiMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_MULT_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setMultiMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_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 MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getWaitForExternalSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, buffer); + return buffer[0]; +} +/** Set wait-for-external-sensor-data enabled value. + * @param enabled New wait-for-external-sensor-data enabled value + * @see getWaitForExternalSensorEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, enabled); +} +/** Get Slave 3 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 3 to be written into the FIFO buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU9150_RA_MST_CTRL + */ +bool MPU9150::getSlave3FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_SLV_3_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see MPU9150_RA_MST_CTRL + */ +void MPU9150::setSlave3FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_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 MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getSlaveReadWriteTransitionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_P_NSR_BIT, buffer); + return buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_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 MPU9150_RA_I2C_MST_CTRL + */ +uint8_t MPU9150::getMasterClockSpeed() { + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_I2C_MST_CLK_LENGTH, buffer); + return buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setMasterClockSpeed(uint8_t speed) { + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_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-9150 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 MPU9150_RA_I2C_SLV0_ADDR + */ +uint8_t MPU9150::getSlaveAddress(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_ADDR + num*3, buffer); + return buffer[0]; +} +/** Set the I2C address of the specified slave (0-3). + * @param num Slave number (0-3) + * @param address New address for specified slave + * @see getSlaveAddress() + * @see MPU9150_RA_I2C_SLV0_ADDR + */ +void MPU9150::setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_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-9150 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 MPU9150_RA_I2C_SLV0_REG + */ +uint8_t MPU9150::getSlaveRegister(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_REG + num*3, buffer); + return buffer[0]; +} +/** Set the active internal register for the specified slave (0-3). + * @param num Slave number (0-3) + * @param reg New active register for specified slave + * @see getSlaveRegister() + * @see MPU9150_RA_I2C_SLV0_REG + */ +void MPU9150::setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveEnabled(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New enabled value for specified slave + * @see getSlaveEnabled() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_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 MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWordByteSwap(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_BYTE_SW_BIT, buffer); + return buffer[0]; +} +/** Set word pair byte-swapping enabled for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair byte-swapping enabled value for specified slave + * @see getSlaveWordByteSwap() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_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 MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWriteMode(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the specified slave (0-3). + * @param num Slave number (0-3) + * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) + * @see getSlaveWriteMode() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_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 MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_GRP_BIT, buffer); + return buffer[0]; +} +/** Set word pair grouping order offset for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair grouping order offset for specified slave + * @see getSlaveWordGroupOffset() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_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 MPU9150_RA_I2C_SLV0_CTRL + */ +uint8_t MPU9150::getSlaveDataLength(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_I2C_SLV_LEN_LENGTH, buffer); + return buffer[0]; +} +/** Set number of bytes to read for the specified slave (0-3). + * @param num Slave number (0-3) + * @param length Number of bytes to read for specified slave + * @see getSlaveDataLength() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) return; + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_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 MPU9150_RA_I2C_SLV4_ADDR + */ +uint8_t MPU9150::getSlave4Address() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_ADDR, buffer); + return buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see MPU9150_RA_I2C_SLV4_ADDR + */ +void MPU9150::setSlave4Address(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_I2C_SLV4_REG + */ +uint8_t MPU9150::getSlave4Register() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_REG, buffer); + return buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see MPU9150_RA_I2C_SLV4_REG + */ +void MPU9150::setSlave4Register(uint8_t reg) { + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_I2C_SLV4_DO + */ +void MPU9150::setSlave4OutputByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4Enabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4Enabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_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 MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4InterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4 transaction interrupts. + * @param enabled New enabled value for Slave 4 transaction interrupts. + * @see getSlave4InterruptEnabled() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_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 MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4WriteMode() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the Slave 4. + * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see getSlave4WriteMode() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4WriteMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_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 MPU9150_RA_I2C_SLV4_CTRL + */ +uint8_t MPU9150::getSlave4MasterDelay() { + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_I2C_SLV4_MST_DLY_LENGTH, buffer); + return buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4MasterDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_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 MPU9150_RA_I2C_SLV4_DI + */ +uint8_t MPU9150::getSlate4InputByte() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_DI, buffer); + return buffer[0]; +} + +// I2C_MST_STATUS register + +/** Get FSYNC interrupt status. + * This bit reflects the status of the FSYNC interrupt from an external device + * into the MPU-60X0. This is used as a way to pass an external interrupt + * through the MPU-60X0 to the host application processor. When set to 1, this + * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG + * (Register 55). + * @return FSYNC interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getPassthroughStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_PASS_THROUGH_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 transaction done status. + * Automatically sets to 1 when a Slave 4 transaction has completed. This + * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register + * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the + * I2C_SLV4_CTRL register (Register 52). + * @return Slave 4 transaction done status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave4IsDone() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_DONE_BIT, buffer); + return buffer[0]; +} +/** Get master arbitration lost status. + * This bit automatically sets to 1 when the I2C Master has lost arbitration of + * the auxiliary I2C bus (an error condition). This triggers an interrupt if the + * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. + * @return Master arbitration lost status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getLostArbitration() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_LOST_ARB_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 4 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave4Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 3 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 3 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave3Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV3_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 2 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 2 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave2Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV2_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 1 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 1 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave1Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV1_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 0 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 0 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave0Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV0_NACK_BIT, buffer); + return buffer[0]; +} + +// INT_PIN_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_LEVEL_BIT + */ +bool MPU9150::getInterruptMode() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_LEVEL_BIT + */ +void MPU9150::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_OPEN_BIT + */ +bool MPU9150::getInterruptDrive() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_OPEN_BIT + */ +void MPU9150::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_LATCH_INT_EN_BIT + */ +bool MPU9150::getInterruptLatch() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_LATCH_INT_EN_BIT + */ +void MPU9150::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT + */ +bool MPU9150::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_RD_CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT + */ +void MPU9150::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool MPU9150::getFSyncInterruptLevel() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC interrupt logic level mode. + * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void MPU9150::setFSyncInterruptLevel(bool level) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT + */ +bool MPU9150::getFSyncInterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT + */ +void MPU9150::setFSyncInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT + */ +bool MPU9150::getI2CBypassEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_I2C_BYPASS_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @param enabled New I2C bypass enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT + */ +void MPU9150::setI2CBypassEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_CLKOUT_EN_BIT + */ +bool MPU9150::getClockOutputEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_CLKOUT_EN_BIT, buffer); + return buffer[0]; +} +/** Set reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @param enabled New reference clock output enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_CLKOUT_EN_BIT + */ +void MPU9150::setClockOutputEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +uint8_t MPU9150::getIntEnabled() { + I2Cdev::readByte(devAddr, MPU9150_RA_INT_ENABLE, buffer); + return buffer[0]; +} +/** Set full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit should be + * set 0 for disabled, 1 for enabled. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +void MPU9150::setIntEnabled(uint8_t enabled) { + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +bool MPU9150::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +void MPU9150::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_MOT_BIT + **/ +bool MPU9150::getIntMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_MOT_BIT + **/ +void MPU9150::setIntMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_ZMOT_BIT + **/ +bool MPU9150::getIntZeroMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_ZMOT_BIT + **/ +void MPU9150::setIntZeroMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool MPU9150::getIntFIFOBufferOverflowEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + **/ +void MPU9150::setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + **/ +bool MPU9150::getIntI2CMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + **/ +void MPU9150::setIntI2CMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9150::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see MPU9150_RA_INT_CFG + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +void MPU9150::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_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 MPU9150_RA_INT_STATUS + */ +uint8_t MPU9150::getIntStatus() { + I2Cdev::readByte(devAddr, MPU9150_RA_INT_STATUS, buffer); + return buffer[0]; +} +/** Get Free Fall interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_FF_BIT + */ +bool MPU9150::getIntFreefallStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Get Motion Detection interrupt status. + * This bit automatically sets to 1 when a Motion Detection interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_MOT_BIT + */ +bool MPU9150::getIntMotionStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Get Zero Motion Detection interrupt status. + * This bit automatically sets to 1 when a Zero Motion Detection interrupt has + * been generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_ZMOT_BIT + */ +bool MPU9150::getIntZeroMotionStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Get FIFO Buffer Overflow interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + */ +bool MPU9150::getIntFIFOBufferOverflowStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Get I2C Master interrupt status. + * This bit automatically sets to 1 when an I2C Master interrupt has been + * generated. For a list of I2C Master interrupts, please refer to Register 54. + * The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + */ +bool MPU9150::getIntI2CMasterStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * This bit automatically sets to 1 when a Data Ready interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9150::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} + +// ACCEL_*OUT_* registers + +/** Get raw 9-axis motion sensor readings (accel/gyro/compass). + * FUNCTION NOT FULLY IMPLEMENTED YET. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @param mx 16-bit signed integer container for magnetometer X-axis value + * @param my 16-bit signed integer container for magnetometer Y-axis value + * @param mz 16-bit signed integer container for magnetometer Z-axis value + * @see getMotion6() + * @see getAcceleration() + * @see getRotation() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +void MPU9150::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) { + + //get accel and gyro + getMotion6(ax, ay, az, gx, gy, gz); + + //read mag + I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer + delay(10); + I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer + delay(10); + I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); + *mx = (((int16_t)buffer[0]) << 8) | buffer[1]; + *my = (((int16_t)buffer[2]) << 8) | buffer[3]; + *mz = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get raw 6-axis motion sensor readings (accel/gyro). + * Retrieves all currently available motion sensor values. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @see getAcceleration() + * @see getRotation() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +void MPU9150::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 14, buffer); + *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; + *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; + *az = (((int16_t)buffer[4]) << 8) | buffer[5]; + *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; + *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; + *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; +} +/** Get 3-axis accelerometer readings. + * These registers store the most recent accelerometer measurements. + * Accelerometer measurements are written to these registers at the Sample Rate + * as defined in Register 25. + * + * The accelerometer measurement registers, along with the temperature + * measurement registers, gyroscope measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * + * The data within the accelerometer sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS + * (Register 28). For each full scale setting, the accelerometers' sensitivity + * per LSB in ACCEL_xOUT is shown in the table below: + * + *
+ * 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 MPU9150_RA_GYRO_XOUT_H + */ +void MPU9150::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +int16_t MPU9150::getAccelerationX() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_YOUT_H + */ +int16_t MPU9150::getAccelerationY() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_ZOUT_H + */ +int16_t MPU9150::getAccelerationZ() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see MPU9150_RA_TEMP_OUT_H + */ +int16_t MPU9150::getTemperature() { + I2Cdev::readBytes(devAddr, MPU9150_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +void MPU9150::getHeading(int16_t* mx, int16_t* my, int16_t* mz) { + //read mag + I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer + delay(10); + I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer + delay(10); + I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); + *mx = (((int16_t)buffer[0]) << 8) | buffer[1]; + *my = (((int16_t)buffer[2]) << 8) | buffer[3]; + *mz = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +// 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 MPU9150_RA_GYRO_XOUT_H + */ +void MPU9150::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_XOUT_H + */ +int16_t MPU9150::getRotationX() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_YOUT_H + */ +int16_t MPU9150::getRotationY() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_ZOUT_H + */ +int16_t MPU9150::getRotationZ() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// EXT_SENS_DATA_* registers + +/** Read single byte from external sensor data register. + * These registers store data read from external sensors by the Slave 0, 1, 2, + * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in + * I2C_SLV4_DI (Register 53). + * + * External sensor data is written to these registers at the Sample Rate as + * defined in Register 25. This access rate can be reduced by using the Slave + * Delay Enable registers (Register 103). + * + * External sensor data registers, along with the gyroscope measurement + * registers, accelerometer measurement registers, and temperature measurement + * registers, are composed of two sets of registers: an internal register set + * and a user-facing read register set. + * + * The data within the external sensors' internal register set is always updated + * at the Sample Rate (or the reduced access rate) whenever the serial interface + * is idle. This guarantees that a burst read of sensor registers will read + * measurements from the same sampling instant. Note that if burst reads are not + * used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Data is placed in these external sensor data registers according to + * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, + * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from + * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as + * defined in Register 25) or delayed rate (if specified in Register 52 and + * 103). During each Sample cycle, slave reads are performed in order of Slave + * number. If all slaves are enabled with more than zero bytes to be read, the + * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. + * + * Each enabled slave will have EXT_SENS_DATA registers associated with it by + * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from + * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may + * change the higher numbered slaves' associated registers. Furthermore, if + * fewer total bytes are being read from the external sensors as a result of + * such a change, then the data remaining in the registers which no longer have + * an associated slave device (i.e. high numbered registers) will remain in + * these previously allocated registers unless reset. + * + * If the sum of the read lengths of all SLVx transactions exceed the number of + * available EXT_SENS_DATA registers, the excess bytes will be dropped. There + * are 24 EXT_SENS_DATA registers and hence the total read lengths between all + * the slaves cannot be greater than 24 or some bytes will be lost. + * + * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further + * information regarding the characteristics of Slave 4, please refer to + * Registers 49 to 53. + * + * EXAMPLE: + * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and + * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that + * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 + * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 + * will be associated with Slave 1. If Slave 2 is enabled as well, registers + * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. + * + * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then + * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 + * instead. + * + * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: + * If a slave is disabled at any time, the space initially allocated to the + * slave in the EXT_SENS_DATA register, will remain associated with that slave. + * This is to avoid dynamic adjustment of the register allocation. + * + * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all + * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). + * + * This above is also true if one of the slaves gets NACKed and stops + * functioning. + * + * @param position Starting position (0-23) + * @return Byte read from register + */ +uint8_t MPU9150::getExternalSensorByte(int position) { + I2Cdev::readByte(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, buffer); + return buffer[0]; +} +/** Read word (2 bytes) from external sensor data registers. + * @param position Starting position (0-21) + * @return Word read from register + * @see getExternalSensorByte() + */ +uint16_t MPU9150::getExternalSensorWord(int position) { + I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} +/** Read double word (4 bytes) from external sensor data registers. + * @param position Starting position (0-20) + * @return Double word read from registers + * @see getExternalSensorByte() + */ +uint32_t MPU9150::getExternalSensorDWord(int position) { + I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 4, buffer); + return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; +} + +// MOT_DETECT_STATUS register + +/** Get X-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_XNEG_BIT + */ +bool MPU9150::getXNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XNEG_BIT, buffer); + return buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_XPOS_BIT + */ +bool MPU9150::getXPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XPOS_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_YNEG_BIT + */ +bool MPU9150::getYNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YNEG_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_YPOS_BIT + */ +bool MPU9150::getYPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YPOS_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZNEG_BIT + */ +bool MPU9150::getZNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZNEG_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZPOS_BIT + */ +bool MPU9150::getZPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZPOS_BIT, buffer); + return buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZRMOT_BIT + */ +bool MPU9150::getZeroMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZRMOT_BIT, buffer); + return buffer[0]; +} + +// I2C_SLV*_DO register + +/** Write byte to Data Output container for specified slave. + * This register holds the output data written into Slave when Slave is set to + * write mode. For further information regarding Slave control, please + * refer to Registers 37 to 39 and immediately following. + * @param num Slave number (0-3) + * @param data Byte to write + * @see MPU9150_RA_I2C_SLV0_DO + */ +void MPU9150::setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool MPU9150::getExternalShadowDelayEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); + return buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void MPU9150::setExternalShadowDelayEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_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 MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool MPU9150::getSlaveDelayEnabled(uint8_t num) { + // MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, num, buffer); + return buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void MPU9150::setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_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 MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_GYRO_RESET_BIT + */ +void MPU9150::resetGyroscopePath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_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 MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_ACCEL_RESET_BIT + */ +void MPU9150::resetAccelerometerPath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_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 MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_TEMP_RESET_BIT + */ +void MPU9150::resetTemperaturePath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_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-9150 Product Specification document for + * further information regarding the detection modules. + * @return Current accelerometer power-on delay + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t MPU9150::getAccelerometerPowerOnDelay() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); + return buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT + */ +void MPU9150::setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_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 MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_FF_COUNT_BIT + */ +uint8_t MPU9150::getFreefallDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_DETECT_FF_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_FF_COUNT_BIT + */ +void MPU9150::setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_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 MPU9150::getMotionDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_MOT_COUNT_BIT + */ +void MPU9150::setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, decrement); +} + +// USER_CTRL register + +/** Get FIFO enabled status. + * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer + * cannot be written to or read from while disabled. The FIFO buffer's state + * does not change unless the MPU-60X0 is power cycled. + * @return Current FIFO enabled status + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_EN_BIT + */ +bool MPU9150::getFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_EN_BIT + */ +void MPU9150::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_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 MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_EN_BIT + */ +bool MPU9150::getI2CMasterModeEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_EN_BIT + */ +void MPU9150::setI2CMasterModeEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_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 MPU9150::switchSPIEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This + * bit automatically clears to 0 after the reset has been triggered. + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_RESET_BIT + */ +void MPU9150::resetFIFO() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_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 MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_RESET_BIT + */ +void MPU9150::resetI2CMaster() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_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 MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_SIG_COND_RESET_BIT + */ +void MPU9150::resetSensors() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_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 MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_DEVICE_RESET_BIT + */ +void MPU9150::reset() { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_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 MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_SLEEP_BIT + */ +bool MPU9150::getSleepEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_SLEEP_BIT + */ +void MPU9150::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_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 MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CYCLE_BIT + */ +bool MPU9150::getWakeCycleEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CYCLE_BIT, buffer); + return buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CYCLE_BIT + */ +void MPU9150::setWakeCycleEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_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 MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_TEMP_DIS_BIT + */ +bool MPU9150::getTempSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, buffer); + return buffer[0] == 0; // 1 is actually disabled here +} +/** Set temperature sensor enabled status. + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @param enabled New temperature sensor enabled status + * @see getTempSensorEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_TEMP_DIS_BIT + */ +void MPU9150::setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CLKSEL_BIT + * @see MPU9150_PWR1_CLKSEL_LENGTH + */ +uint8_t MPU9150::getClockSource() { + I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_PWR1_CLKSEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * An internal 8MHz oscillator, gyroscope based clock, or external sources can + * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator + * or an external source is chosen as the clock source, the MPU-60X0 can operate + * in low power modes with the gyroscopes disabled. + * + * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. + * However, it is highly recommended that the device be configured to use one of + * the gyroscopes (or an external clock source) as the clock reference for + * improved stability. The clock source can be selected according to the following table: + * + *
+ * 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 MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CLKSEL_BIT + * @see MPU9150_PWR1_CLKSEL_LENGTH + */ +void MPU9150::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ */
+uint8_t MPU9150::getWakeFrequency() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU9150_RA_PWR_MGMT_2
+ */
+void MPU9150::setWakeFrequency(uint8_t frequency) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XA_BIT
+ */
+bool MPU9150::getStandbyXAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XA_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XA_BIT
+ */
+void MPU9150::setStandbyXAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YA_BIT
+ */
+bool MPU9150::getStandbyYAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YA_BIT
+ */
+void MPU9150::setStandbyYAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZA_BIT
+ */
+bool MPU9150::getStandbyZAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZA_BIT
+ */
+void MPU9150::setStandbyZAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XG_BIT
+ */
+bool MPU9150::getStandbyXGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XG_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XG_BIT
+ */
+void MPU9150::setStandbyXGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YG_BIT
+ */
+bool MPU9150::getStandbyYGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YG_BIT
+ */
+void MPU9150::setStandbyYGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_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 MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZG_BIT
+ */
+bool MPU9150::getStandbyZGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZG_BIT
+ */
+void MPU9150::setStandbyZGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU9150::getFIFOCount() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_COUNTH, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU9150::getFIFOByte() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_FIFO_R_W, buffer);
+    return buffer[0];
+}
+void MPU9150::getFIFOBytes(uint8_t *data, uint8_t length) {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU9150_RA_FIFO_R_W
+ */
+void MPU9150::setFIFOByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9150_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 MPU9150_RA_WHO_AM_I
+ * @see MPU9150_WHO_AM_I_BIT
+ * @see MPU9150_WHO_AM_I_LENGTH
+ */
+uint8_t MPU9150::getDeviceID() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU9150_RA_WHO_AM_I
+ * @see MPU9150_WHO_AM_I_BIT
+ * @see MPU9150_WHO_AM_I_LENGTH
+ */
+void MPU9150::setDeviceID(uint8_t id) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU9150::getOTPBankValid() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setOTPBankValid(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU9150::getXGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setXGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU9150::getYGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setYGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU9150::getZGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setZGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU9150::getXFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_X_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setXFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU9150::getYFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_Y_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setYFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU9150::getZFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_Z_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setZFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU9150::getXAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_XA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setXAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU9150::getYAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_YA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setYAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU9150::getZAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_ZA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setZAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU9150::getXGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_XG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setXGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU9150::getYGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_YG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setYGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU9150::getZGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_ZG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setZGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU9150::getIntPLLReadyEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setIntPLLReadyEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU9150::getIntDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setIntDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU9150::getDMPInt5Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_5_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt4Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_4_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt3Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_3_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt2Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_2_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt1Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_1_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt0Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_0_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU9150::getIntPLLReadyStatus() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getIntDMPStatus() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU9150::getDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU9150::resetDMP() {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU9150::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
+    bank &= 0x1F;
+    if (userBank) bank |= 0x20;
+    if (prefetchEnabled) bank |= 0x40;
+    I2Cdev::writeByte(devAddr, MPU9150_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU9150::setMemoryStartAddress(uint8_t address) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU9150::readMemoryByte() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_MEM_R_W, buffer);
+    return buffer[0];
+}
+void MPU9150::writeMemoryByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_R_W, data);
+}
+void MPU9150::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        // read the chunk of data as specified
+        I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, data + i);
+        
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+}
+bool MPU9150::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer;
+    uint8_t *progBuffer;
+    uint16_t i;
+    uint8_t j;
+    if (verify) verifyBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
+    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
+    else progBuffer = NULL;
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+        
+        if (useProgMem) {
+            // write the chunk of data as specified
+            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+        } else {
+            // write the chunk of data as specified
+            progBuffer = (uint8_t *)data + i;
+        }
+
+        I2Cdev::writeBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+            I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, verifyBuffer);
+            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+                /*Serial.print("Block write verification error, bank ");
+                Serial.print(bank, DEC);
+                Serial.print(", address ");
+                Serial.print(address, DEC);
+                Serial.print("!\nExpected:");
+                for (j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (progBuffer[j] < 16) Serial.print("0");
+                    Serial.print(progBuffer[j], HEX);
+                }
+                Serial.print("\nReceived:");
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (verifyBuffer[i + j] < 16) Serial.print("0");
+                    Serial.print(verifyBuffer[i + j], HEX);
+                }
+                Serial.print("\n");*/
+                free(verifyBuffer);
+                if (useProgMem) free(progBuffer);
+                return false; // uh oh.
+            }
+        }
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+    if (verify) free(verifyBuffer);
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9150::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
+    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU9150::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
+    } else {
+        progBuffer = NULL;
+    }
+
+    // config set data is a long string of blocks with the following structure:
+    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+    uint8_t bank, offset, length;
+    for (i = 0; i < dataSize;) {
+        if (useProgMem) {
+            bank = pgm_read_byte(data + i++);
+            offset = pgm_read_byte(data + i++);
+            length = pgm_read_byte(data + i++);
+        } else {
+            bank = data[i++];
+            offset = data[i++];
+            length = data[i++];
+        }
+
+        // write data or perform special action
+        if (length > 0) {
+            // regular block of data to write
+            /*Serial.print("Writing config block to bank ");
+            Serial.print(bank);
+            Serial.print(", offset ");
+            Serial.print(offset);
+            Serial.print(", length=");
+            Serial.println(length);*/
+            if (useProgMem) {
+                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+            } else {
+                progBuffer = (uint8_t *)data + i;
+            }
+            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+            i += length;
+        } else {
+            // special instruction
+            // NOTE: this kind of behavior (what and when to do certain things)
+            // is totally undocumented. This code is in here based on observed
+            // behavior only, and exactly why (or even whether) it has to be here
+            // is anybody's guess for now.
+            if (useProgMem) {
+                special = pgm_read_byte(data + i++);
+            } else {
+                special = data[i++];
+            }
+            /*Serial.print("Special command code ");
+            Serial.print(special, HEX);
+            Serial.println(" found...");*/
+            if (special == 0x01) {
+                // enable DMP-related interrupts
+                
+                //setIntZeroMotionEnabled(true);
+                //setIntFIFOBufferOverflowEnabled(true);
+                //setIntDMPEnabled(true);
+                I2Cdev::writeByte(devAddr, MPU9150_RA_INT_ENABLE, 0x32);  // single operation
+
+                success = true;
+            } else {
+                // unknown special command
+                success = false;
+            }
+        }
+        
+        if (!success) {
+            if (useProgMem) free(progBuffer);
+            return false; // uh oh
+        }
+    }
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9150::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
+    return writeDMPConfigurationSet(data, dataSize, true);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU9150::getDMPConfig1() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_1, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPConfig1(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU9150::getDMPConfig2() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_2, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPConfig2(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_2, config);
+}
diff --git a/firmware/lib/imu/MPU9150.h b/firmware/lib/imu/MPU9150.h
new file mode 100644
index 0000000..8e3f939
--- /dev/null
+++ b/firmware/lib/imu/MPU9150.h
@@ -0,0 +1,1040 @@
+// I2Cdev library collection - MPU9150 I2C device class
+// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU9150_H_
+#define _MPU9150_H_
+
+#include "I2Cdev.h"
+
+// // Tom Carpenter's conditional PROGMEM code
+// // http://forum.arduino.cc/index.php?topic=129407.0
+// #ifdef __AVR__
+//     #include 
+// #else
+//     // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+//     #ifndef __PGMSPACE_H_
+//         #define __PGMSPACE_H_ 1
+//         #include 
+
+//         #define PROGMEM
+//         #define PGM_P  const char *
+//         #define PSTR(str) (str)
+//         #define F(x) x
+
+//         typedef void prog_void;
+//         typedef char prog_char;
+//         typedef unsigned char prog_uchar;
+//         typedef int8_t prog_int8_t;
+//         typedef uint8_t prog_uint8_t;
+//         typedef int16_t prog_int16_t;
+//         typedef uint16_t prog_uint16_t;
+//         typedef int32_t prog_int32_t;
+//         typedef uint32_t prog_uint32_t;
+
+//         #define strcpy_P(dest, src) strcpy((dest), (src))
+//         #define strcat_P(dest, src) strcat((dest), (src))
+//         #define strcmp_P(a, b) strcmp((a), (b))
+
+//         #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+//         #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+//         #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+//         #define pgm_read_float(addr) (*(const float *)(addr))
+
+//         #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+//         #define pgm_read_word_near(addr) pgm_read_word(addr)
+//         #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+//         #define pgm_read_float_near(addr) pgm_read_float(addr)
+//         #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+//         #define pgm_read_word_far(addr) pgm_read_word(addr)
+//         #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+//         #define pgm_read_float_far(addr) pgm_read_float(addr)
+//     #endif
+// #endif
+
+//Magnetometer Registers
+#define MPU9150_RA_MAG_ADDRESS		0x0C
+#define MPU9150_RA_MAG_XOUT_L		0x03
+#define MPU9150_RA_MAG_XOUT_H		0x04
+#define MPU9150_RA_MAG_YOUT_L		0x05
+#define MPU9150_RA_MAG_YOUT_H		0x06
+#define MPU9150_RA_MAG_ZOUT_L		0x07
+#define MPU9150_RA_MAG_ZOUT_H		0x08
+
+#define MPU9150_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU9150_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU9150_DEFAULT_ADDRESS     MPU9150_ADDRESS_AD0_LOW
+
+#define MPU9150_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU9150_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU9150_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU9150_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU9150_RA_XA_OFFS_L_TC     0x07
+#define MPU9150_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU9150_RA_YA_OFFS_L_TC     0x09
+#define MPU9150_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU9150_RA_ZA_OFFS_L_TC     0x0B
+#define MPU9150_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU9150_RA_XG_OFFS_USRL     0x14
+#define MPU9150_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU9150_RA_YG_OFFS_USRL     0x16
+#define MPU9150_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU9150_RA_ZG_OFFS_USRL     0x18
+#define MPU9150_RA_SMPLRT_DIV       0x19
+#define MPU9150_RA_CONFIG           0x1A
+#define MPU9150_RA_GYRO_CONFIG      0x1B
+#define MPU9150_RA_ACCEL_CONFIG     0x1C
+#define MPU9150_RA_FF_THR           0x1D
+#define MPU9150_RA_FF_DUR           0x1E
+#define MPU9150_RA_MOT_THR          0x1F
+#define MPU9150_RA_MOT_DUR          0x20
+#define MPU9150_RA_ZRMOT_THR        0x21
+#define MPU9150_RA_ZRMOT_DUR        0x22
+#define MPU9150_RA_FIFO_EN          0x23
+#define MPU9150_RA_I2C_MST_CTRL     0x24
+#define MPU9150_RA_I2C_SLV0_ADDR    0x25
+#define MPU9150_RA_I2C_SLV0_REG     0x26
+#define MPU9150_RA_I2C_SLV0_CTRL    0x27
+#define MPU9150_RA_I2C_SLV1_ADDR    0x28
+#define MPU9150_RA_I2C_SLV1_REG     0x29
+#define MPU9150_RA_I2C_SLV1_CTRL    0x2A
+#define MPU9150_RA_I2C_SLV2_ADDR    0x2B
+#define MPU9150_RA_I2C_SLV2_REG     0x2C
+#define MPU9150_RA_I2C_SLV2_CTRL    0x2D
+#define MPU9150_RA_I2C_SLV3_ADDR    0x2E
+#define MPU9150_RA_I2C_SLV3_REG     0x2F
+#define MPU9150_RA_I2C_SLV3_CTRL    0x30
+#define MPU9150_RA_I2C_SLV4_ADDR    0x31
+#define MPU9150_RA_I2C_SLV4_REG     0x32
+#define MPU9150_RA_I2C_SLV4_DO      0x33
+#define MPU9150_RA_I2C_SLV4_CTRL    0x34
+#define MPU9150_RA_I2C_SLV4_DI      0x35
+#define MPU9150_RA_I2C_MST_STATUS   0x36
+#define MPU9150_RA_INT_PIN_CFG      0x37
+#define MPU9150_RA_INT_ENABLE       0x38
+#define MPU9150_RA_DMP_INT_STATUS   0x39
+#define MPU9150_RA_INT_STATUS       0x3A
+#define MPU9150_RA_ACCEL_XOUT_H     0x3B
+#define MPU9150_RA_ACCEL_XOUT_L     0x3C
+#define MPU9150_RA_ACCEL_YOUT_H     0x3D
+#define MPU9150_RA_ACCEL_YOUT_L     0x3E
+#define MPU9150_RA_ACCEL_ZOUT_H     0x3F
+#define MPU9150_RA_ACCEL_ZOUT_L     0x40
+#define MPU9150_RA_TEMP_OUT_H       0x41
+#define MPU9150_RA_TEMP_OUT_L       0x42
+#define MPU9150_RA_GYRO_XOUT_H      0x43
+#define MPU9150_RA_GYRO_XOUT_L      0x44
+#define MPU9150_RA_GYRO_YOUT_H      0x45
+#define MPU9150_RA_GYRO_YOUT_L      0x46
+#define MPU9150_RA_GYRO_ZOUT_H      0x47
+#define MPU9150_RA_GYRO_ZOUT_L      0x48
+#define MPU9150_RA_EXT_SENS_DATA_00 0x49
+#define MPU9150_RA_EXT_SENS_DATA_01 0x4A
+#define MPU9150_RA_EXT_SENS_DATA_02 0x4B
+#define MPU9150_RA_EXT_SENS_DATA_03 0x4C
+#define MPU9150_RA_EXT_SENS_DATA_04 0x4D
+#define MPU9150_RA_EXT_SENS_DATA_05 0x4E
+#define MPU9150_RA_EXT_SENS_DATA_06 0x4F
+#define MPU9150_RA_EXT_SENS_DATA_07 0x50
+#define MPU9150_RA_EXT_SENS_DATA_08 0x51
+#define MPU9150_RA_EXT_SENS_DATA_09 0x52
+#define MPU9150_RA_EXT_SENS_DATA_10 0x53
+#define MPU9150_RA_EXT_SENS_DATA_11 0x54
+#define MPU9150_RA_EXT_SENS_DATA_12 0x55
+#define MPU9150_RA_EXT_SENS_DATA_13 0x56
+#define MPU9150_RA_EXT_SENS_DATA_14 0x57
+#define MPU9150_RA_EXT_SENS_DATA_15 0x58
+#define MPU9150_RA_EXT_SENS_DATA_16 0x59
+#define MPU9150_RA_EXT_SENS_DATA_17 0x5A
+#define MPU9150_RA_EXT_SENS_DATA_18 0x5B
+#define MPU9150_RA_EXT_SENS_DATA_19 0x5C
+#define MPU9150_RA_EXT_SENS_DATA_20 0x5D
+#define MPU9150_RA_EXT_SENS_DATA_21 0x5E
+#define MPU9150_RA_EXT_SENS_DATA_22 0x5F
+#define MPU9150_RA_EXT_SENS_DATA_23 0x60
+#define MPU9150_RA_MOT_DETECT_STATUS    0x61
+#define MPU9150_RA_I2C_SLV0_DO      0x63
+#define MPU9150_RA_I2C_SLV1_DO      0x64
+#define MPU9150_RA_I2C_SLV2_DO      0x65
+#define MPU9150_RA_I2C_SLV3_DO      0x66
+#define MPU9150_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU9150_RA_SIGNAL_PATH_RESET    0x68
+#define MPU9150_RA_MOT_DETECT_CTRL      0x69
+#define MPU9150_RA_USER_CTRL        0x6A
+#define MPU9150_RA_PWR_MGMT_1       0x6B
+#define MPU9150_RA_PWR_MGMT_2       0x6C
+#define MPU9150_RA_BANK_SEL         0x6D
+#define MPU9150_RA_MEM_START_ADDR   0x6E
+#define MPU9150_RA_MEM_R_W          0x6F
+#define MPU9150_RA_DMP_CFG_1        0x70
+#define MPU9150_RA_DMP_CFG_2        0x71
+#define MPU9150_RA_FIFO_COUNTH      0x72
+#define MPU9150_RA_FIFO_COUNTL      0x73
+#define MPU9150_RA_FIFO_R_W         0x74
+#define MPU9150_RA_WHO_AM_I         0x75
+
+#define MPU9150_TC_PWR_MODE_BIT     7
+#define MPU9150_TC_OFFSET_BIT       6
+#define MPU9150_TC_OFFSET_LENGTH    6
+#define MPU9150_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU9150_VDDIO_LEVEL_VLOGIC  0
+#define MPU9150_VDDIO_LEVEL_VDD     1
+
+#define MPU9150_CFG_EXT_SYNC_SET_BIT    5
+#define MPU9150_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU9150_CFG_DLPF_CFG_BIT    2
+#define MPU9150_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU9150_EXT_SYNC_DISABLED       0x0
+#define MPU9150_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU9150_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU9150_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU9150_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU9150_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU9150_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU9150_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU9150_DLPF_BW_256         0x00
+#define MPU9150_DLPF_BW_188         0x01
+#define MPU9150_DLPF_BW_98          0x02
+#define MPU9150_DLPF_BW_42          0x03
+#define MPU9150_DLPF_BW_20          0x04
+#define MPU9150_DLPF_BW_10          0x05
+#define MPU9150_DLPF_BW_5           0x06
+
+#define MPU9150_GCONFIG_FS_SEL_BIT      4
+#define MPU9150_GCONFIG_FS_SEL_LENGTH   2
+
+#define MPU9150_GYRO_FS_250         0x00
+#define MPU9150_GYRO_FS_500         0x01
+#define MPU9150_GYRO_FS_1000        0x02
+#define MPU9150_GYRO_FS_2000        0x03
+
+#define MPU9150_ACONFIG_XA_ST_BIT           7
+#define MPU9150_ACONFIG_YA_ST_BIT           6
+#define MPU9150_ACONFIG_ZA_ST_BIT           5
+#define MPU9150_ACONFIG_AFS_SEL_BIT         4
+#define MPU9150_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU9150_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU9150_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU9150_ACCEL_FS_2          0x00
+#define MPU9150_ACCEL_FS_4          0x01
+#define MPU9150_ACCEL_FS_8          0x02
+#define MPU9150_ACCEL_FS_16         0x03
+
+#define MPU9150_DHPF_RESET          0x00
+#define MPU9150_DHPF_5              0x01
+#define MPU9150_DHPF_2P5            0x02
+#define MPU9150_DHPF_1P25           0x03
+#define MPU9150_DHPF_0P63           0x04
+#define MPU9150_DHPF_HOLD           0x07
+
+#define MPU9150_TEMP_FIFO_EN_BIT    7
+#define MPU9150_XG_FIFO_EN_BIT      6
+#define MPU9150_YG_FIFO_EN_BIT      5
+#define MPU9150_ZG_FIFO_EN_BIT      4
+#define MPU9150_ACCEL_FIFO_EN_BIT   3
+#define MPU9150_SLV2_FIFO_EN_BIT    2
+#define MPU9150_SLV1_FIFO_EN_BIT    1
+#define MPU9150_SLV0_FIFO_EN_BIT    0
+
+#define MPU9150_MULT_MST_EN_BIT     7
+#define MPU9150_WAIT_FOR_ES_BIT     6
+#define MPU9150_SLV_3_FIFO_EN_BIT   5
+#define MPU9150_I2C_MST_P_NSR_BIT   4
+#define MPU9150_I2C_MST_CLK_BIT     3
+#define MPU9150_I2C_MST_CLK_LENGTH  4
+
+#define MPU9150_CLOCK_DIV_348       0x0
+#define MPU9150_CLOCK_DIV_333       0x1
+#define MPU9150_CLOCK_DIV_320       0x2
+#define MPU9150_CLOCK_DIV_308       0x3
+#define MPU9150_CLOCK_DIV_296       0x4
+#define MPU9150_CLOCK_DIV_286       0x5
+#define MPU9150_CLOCK_DIV_276       0x6
+#define MPU9150_CLOCK_DIV_267       0x7
+#define MPU9150_CLOCK_DIV_258       0x8
+#define MPU9150_CLOCK_DIV_500       0x9
+#define MPU9150_CLOCK_DIV_471       0xA
+#define MPU9150_CLOCK_DIV_444       0xB
+#define MPU9150_CLOCK_DIV_421       0xC
+#define MPU9150_CLOCK_DIV_400       0xD
+#define MPU9150_CLOCK_DIV_381       0xE
+#define MPU9150_CLOCK_DIV_364       0xF
+
+#define MPU9150_I2C_SLV_RW_BIT      7
+#define MPU9150_I2C_SLV_ADDR_BIT    6
+#define MPU9150_I2C_SLV_ADDR_LENGTH 7
+#define MPU9150_I2C_SLV_EN_BIT      7
+#define MPU9150_I2C_SLV_BYTE_SW_BIT 6
+#define MPU9150_I2C_SLV_REG_DIS_BIT 5
+#define MPU9150_I2C_SLV_GRP_BIT     4
+#define MPU9150_I2C_SLV_LEN_BIT     3
+#define MPU9150_I2C_SLV_LEN_LENGTH  4
+
+#define MPU9150_I2C_SLV4_RW_BIT         7
+#define MPU9150_I2C_SLV4_ADDR_BIT       6
+#define MPU9150_I2C_SLV4_ADDR_LENGTH    7
+#define MPU9150_I2C_SLV4_EN_BIT         7
+#define MPU9150_I2C_SLV4_INT_EN_BIT     6
+#define MPU9150_I2C_SLV4_REG_DIS_BIT    5
+#define MPU9150_I2C_SLV4_MST_DLY_BIT    4
+#define MPU9150_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU9150_MST_PASS_THROUGH_BIT    7
+#define MPU9150_MST_I2C_SLV4_DONE_BIT   6
+#define MPU9150_MST_I2C_LOST_ARB_BIT    5
+#define MPU9150_MST_I2C_SLV4_NACK_BIT   4
+#define MPU9150_MST_I2C_SLV3_NACK_BIT   3
+#define MPU9150_MST_I2C_SLV2_NACK_BIT   2
+#define MPU9150_MST_I2C_SLV1_NACK_BIT   1
+#define MPU9150_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU9150_INTCFG_INT_LEVEL_BIT        7
+#define MPU9150_INTCFG_INT_OPEN_BIT         6
+#define MPU9150_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU9150_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU9150_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU9150_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU9150_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU9150_INTMODE_ACTIVEHIGH  0x00
+#define MPU9150_INTMODE_ACTIVELOW   0x01
+
+#define MPU9150_INTDRV_PUSHPULL     0x00
+#define MPU9150_INTDRV_OPENDRAIN    0x01
+
+#define MPU9150_INTLATCH_50USPULSE  0x00
+#define MPU9150_INTLATCH_WAITCLEAR  0x01
+
+#define MPU9150_INTCLEAR_STATUSREAD 0x00
+#define MPU9150_INTCLEAR_ANYREAD    0x01
+
+#define MPU9150_INTERRUPT_FF_BIT            7
+#define MPU9150_INTERRUPT_MOT_BIT           6
+#define MPU9150_INTERRUPT_ZMOT_BIT          5
+#define MPU9150_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU9150_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU9150_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU9150_INTERRUPT_DMP_INT_BIT       1
+#define MPU9150_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU9150_DMPINT_5_BIT            5
+#define MPU9150_DMPINT_4_BIT            4
+#define MPU9150_DMPINT_3_BIT            3
+#define MPU9150_DMPINT_2_BIT            2
+#define MPU9150_DMPINT_1_BIT            1
+#define MPU9150_DMPINT_0_BIT            0
+
+#define MPU9150_MOTION_MOT_XNEG_BIT     7
+#define MPU9150_MOTION_MOT_XPOS_BIT     6
+#define MPU9150_MOTION_MOT_YNEG_BIT     5
+#define MPU9150_MOTION_MOT_YPOS_BIT     4
+#define MPU9150_MOTION_MOT_ZNEG_BIT     3
+#define MPU9150_MOTION_MOT_ZPOS_BIT     2
+#define MPU9150_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU9150_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU9150_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU9150_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU9150_PATHRESET_GYRO_RESET_BIT    2
+#define MPU9150_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU9150_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU9150_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU9150_DETECT_FF_COUNT_BIT             3
+#define MPU9150_DETECT_FF_COUNT_LENGTH          2
+#define MPU9150_DETECT_MOT_COUNT_BIT            1
+#define MPU9150_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU9150_DETECT_DECREMENT_RESET  0x0
+#define MPU9150_DETECT_DECREMENT_1      0x1
+#define MPU9150_DETECT_DECREMENT_2      0x2
+#define MPU9150_DETECT_DECREMENT_4      0x3
+
+#define MPU9150_USERCTRL_DMP_EN_BIT             7
+#define MPU9150_USERCTRL_FIFO_EN_BIT            6
+#define MPU9150_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU9150_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU9150_USERCTRL_DMP_RESET_BIT          3
+#define MPU9150_USERCTRL_FIFO_RESET_BIT         2
+#define MPU9150_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU9150_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU9150_PWR1_DEVICE_RESET_BIT   7
+#define MPU9150_PWR1_SLEEP_BIT          6
+#define MPU9150_PWR1_CYCLE_BIT          5
+#define MPU9150_PWR1_TEMP_DIS_BIT       3
+#define MPU9150_PWR1_CLKSEL_BIT         2
+#define MPU9150_PWR1_CLKSEL_LENGTH      3
+
+#define MPU9150_CLOCK_INTERNAL          0x00
+#define MPU9150_CLOCK_PLL_XGYRO         0x01
+#define MPU9150_CLOCK_PLL_YGYRO         0x02
+#define MPU9150_CLOCK_PLL_ZGYRO         0x03
+#define MPU9150_CLOCK_PLL_EXT32K        0x04
+#define MPU9150_CLOCK_PLL_EXT19M        0x05
+#define MPU9150_CLOCK_KEEP_RESET        0x07
+
+#define MPU9150_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU9150_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU9150_PWR2_STBY_XA_BIT            5
+#define MPU9150_PWR2_STBY_YA_BIT            4
+#define MPU9150_PWR2_STBY_ZA_BIT            3
+#define MPU9150_PWR2_STBY_XG_BIT            2
+#define MPU9150_PWR2_STBY_YG_BIT            1
+#define MPU9150_PWR2_STBY_ZG_BIT            0
+
+#define MPU9150_WAKE_FREQ_1P25      0x0
+#define MPU9150_WAKE_FREQ_2P5       0x1
+#define MPU9150_WAKE_FREQ_5         0x2
+#define MPU9150_WAKE_FREQ_10        0x3
+
+#define MPU9150_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU9150_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU9150_BANKSEL_MEM_SEL_BIT         4
+#define MPU9150_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU9150_WHO_AM_I_BIT        6
+#define MPU9150_WHO_AM_I_LENGTH     6
+
+#define MPU9150_DMP_MEMORY_BANKS        8
+#define MPU9150_DMP_MEMORY_BANK_SIZE    256
+#define MPU9150_DMP_MEMORY_CHUNK_SIZE   16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU9150 {
+    public:
+        MPU9150();
+        MPU9150(uint8_t address);
+
+        void initialize();
+        bool testConnection();
+
+        // AUX_VDDIO register
+        uint8_t getAuxVDDIOLevel();
+        void setAuxVDDIOLevel(uint8_t level);
+
+        // SMPLRT_DIV register
+        uint8_t getRate();
+        void setRate(uint8_t rate);
+
+        // CONFIG register
+        uint8_t getExternalFrameSync();
+        void setExternalFrameSync(uint8_t sync);
+        uint8_t getDLPFMode();
+        void setDLPFMode(uint8_t bandwidth);
+
+        // GYRO_CONFIG register
+        uint8_t getFullScaleGyroRange();
+        void setFullScaleGyroRange(uint8_t range);
+
+        // ACCEL_CONFIG register
+        bool getAccelXSelfTest();
+        void setAccelXSelfTest(bool enabled);
+        bool getAccelYSelfTest();
+        void setAccelYSelfTest(bool enabled);
+        bool getAccelZSelfTest();
+        void setAccelZSelfTest(bool enabled);
+        uint8_t getFullScaleAccelRange();
+        void setFullScaleAccelRange(uint8_t range);
+        uint8_t getDHPFMode();
+        void setDHPFMode(uint8_t mode);
+
+        // FF_THR register
+        uint8_t getFreefallDetectionThreshold();
+        void setFreefallDetectionThreshold(uint8_t threshold);
+
+        // FF_DUR register
+        uint8_t getFreefallDetectionDuration();
+        void setFreefallDetectionDuration(uint8_t duration);
+
+        // MOT_THR register
+        uint8_t getMotionDetectionThreshold();
+        void setMotionDetectionThreshold(uint8_t threshold);
+
+        // MOT_DUR register
+        uint8_t getMotionDetectionDuration();
+        void setMotionDetectionDuration(uint8_t duration);
+
+        // ZRMOT_THR register
+        uint8_t getZeroMotionDetectionThreshold();
+        void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+        // ZRMOT_DUR register
+        uint8_t getZeroMotionDetectionDuration();
+        void setZeroMotionDetectionDuration(uint8_t duration);
+
+        // FIFO_EN register
+        bool getTempFIFOEnabled();
+        void setTempFIFOEnabled(bool enabled);
+        bool getXGyroFIFOEnabled();
+        void setXGyroFIFOEnabled(bool enabled);
+        bool getYGyroFIFOEnabled();
+        void setYGyroFIFOEnabled(bool enabled);
+        bool getZGyroFIFOEnabled();
+        void setZGyroFIFOEnabled(bool enabled);
+        bool getAccelFIFOEnabled();
+        void setAccelFIFOEnabled(bool enabled);
+        bool getSlave2FIFOEnabled();
+        void setSlave2FIFOEnabled(bool enabled);
+        bool getSlave1FIFOEnabled();
+        void setSlave1FIFOEnabled(bool enabled);
+        bool getSlave0FIFOEnabled();
+        void setSlave0FIFOEnabled(bool enabled);
+
+        // I2C_MST_CTRL register
+        bool getMultiMasterEnabled();
+        void setMultiMasterEnabled(bool enabled);
+        bool getWaitForExternalSensorEnabled();
+        void setWaitForExternalSensorEnabled(bool enabled);
+        bool getSlave3FIFOEnabled();
+        void setSlave3FIFOEnabled(bool enabled);
+        bool getSlaveReadWriteTransitionEnabled();
+        void setSlaveReadWriteTransitionEnabled(bool enabled);
+        uint8_t getMasterClockSpeed();
+        void setMasterClockSpeed(uint8_t speed);
+
+        // I2C_SLV* registers (Slave 0-3)
+        uint8_t getSlaveAddress(uint8_t num);
+        void setSlaveAddress(uint8_t num, uint8_t address);
+        uint8_t getSlaveRegister(uint8_t num);
+        void setSlaveRegister(uint8_t num, uint8_t reg);
+        bool getSlaveEnabled(uint8_t num);
+        void setSlaveEnabled(uint8_t num, bool enabled);
+        bool getSlaveWordByteSwap(uint8_t num);
+        void setSlaveWordByteSwap(uint8_t num, bool enabled);
+        bool getSlaveWriteMode(uint8_t num);
+        void setSlaveWriteMode(uint8_t num, bool mode);
+        bool getSlaveWordGroupOffset(uint8_t num);
+        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+        uint8_t getSlaveDataLength(uint8_t num);
+        void setSlaveDataLength(uint8_t num, uint8_t length);
+
+        // I2C_SLV* registers (Slave 4)
+        uint8_t getSlave4Address();
+        void setSlave4Address(uint8_t address);
+        uint8_t getSlave4Register();
+        void setSlave4Register(uint8_t reg);
+        void setSlave4OutputByte(uint8_t data);
+        bool getSlave4Enabled();
+        void setSlave4Enabled(bool enabled);
+        bool getSlave4InterruptEnabled();
+        void setSlave4InterruptEnabled(bool enabled);
+        bool getSlave4WriteMode();
+        void setSlave4WriteMode(bool mode);
+        uint8_t getSlave4MasterDelay();
+        void setSlave4MasterDelay(uint8_t delay);
+        uint8_t getSlate4InputByte();
+
+        // I2C_MST_STATUS register
+        bool getPassthroughStatus();
+        bool getSlave4IsDone();
+        bool getLostArbitration();
+        bool getSlave4Nack();
+        bool getSlave3Nack();
+        bool getSlave2Nack();
+        bool getSlave1Nack();
+        bool getSlave0Nack();
+
+        // INT_PIN_CFG register
+        bool getInterruptMode();
+        void setInterruptMode(bool mode);
+        bool getInterruptDrive();
+        void setInterruptDrive(bool drive);
+        bool getInterruptLatch();
+        void setInterruptLatch(bool latch);
+        bool getInterruptLatchClear();
+        void setInterruptLatchClear(bool clear);
+        bool getFSyncInterruptLevel();
+        void setFSyncInterruptLevel(bool level);
+        bool getFSyncInterruptEnabled();
+        void setFSyncInterruptEnabled(bool enabled);
+        bool getI2CBypassEnabled();
+        void setI2CBypassEnabled(bool enabled);
+        bool getClockOutputEnabled();
+        void setClockOutputEnabled(bool enabled);
+
+        // INT_ENABLE register
+        uint8_t getIntEnabled();
+        void setIntEnabled(uint8_t enabled);
+        bool getIntFreefallEnabled();
+        void setIntFreefallEnabled(bool enabled);
+        bool getIntMotionEnabled();
+        void setIntMotionEnabled(bool enabled);
+        bool getIntZeroMotionEnabled();
+        void setIntZeroMotionEnabled(bool enabled);
+        bool getIntFIFOBufferOverflowEnabled();
+        void setIntFIFOBufferOverflowEnabled(bool enabled);
+        bool getIntI2CMasterEnabled();
+        void setIntI2CMasterEnabled(bool enabled);
+        bool getIntDataReadyEnabled();
+        void setIntDataReadyEnabled(bool enabled);
+
+        // INT_STATUS register
+        uint8_t getIntStatus();
+        bool getIntFreefallStatus();
+        bool getIntMotionStatus();
+        bool getIntZeroMotionStatus();
+        bool getIntFIFOBufferOverflowStatus();
+        bool getIntI2CMasterStatus();
+        bool getIntDataReadyStatus();
+
+        // ACCEL_*OUT_* registers
+        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getAccelerationX();
+        int16_t getAccelerationY();
+        int16_t getAccelerationZ();
+
+        // TEMP_OUT_* registers
+        int16_t getTemperature();
+        
+        void getHeading(int16_t* mx, int16_t* my, int16_t* mz);
+
+        // GYRO_*OUT_* registers
+        void getRotation(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getRotationX();
+        int16_t getRotationY();
+        int16_t getRotationZ();
+
+        // EXT_SENS_DATA_* registers
+        uint8_t getExternalSensorByte(int position);
+        uint16_t getExternalSensorWord(int position);
+        uint32_t getExternalSensorDWord(int position);
+
+        // MOT_DETECT_STATUS register
+        bool getXNegMotionDetected();
+        bool getXPosMotionDetected();
+        bool getYNegMotionDetected();
+        bool getYPosMotionDetected();
+        bool getZNegMotionDetected();
+        bool getZPosMotionDetected();
+        bool getZeroMotionDetected();
+
+        // I2C_SLV*_DO register
+        void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+        // I2C_MST_DELAY_CTRL register
+        bool getExternalShadowDelayEnabled();
+        void setExternalShadowDelayEnabled(bool enabled);
+        bool getSlaveDelayEnabled(uint8_t num);
+        void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+        // SIGNAL_PATH_RESET register
+        void resetGyroscopePath();
+        void resetAccelerometerPath();
+        void resetTemperaturePath();
+
+        // MOT_DETECT_CTRL register
+        uint8_t getAccelerometerPowerOnDelay();
+        void setAccelerometerPowerOnDelay(uint8_t delay);
+        uint8_t getFreefallDetectionCounterDecrement();
+        void setFreefallDetectionCounterDecrement(uint8_t decrement);
+        uint8_t getMotionDetectionCounterDecrement();
+        void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+        // USER_CTRL register
+        bool getFIFOEnabled();
+        void setFIFOEnabled(bool enabled);
+        bool getI2CMasterModeEnabled();
+        void setI2CMasterModeEnabled(bool enabled);
+        void switchSPIEnabled(bool enabled);
+        void resetFIFO();
+        void resetI2CMaster();
+        void resetSensors();
+
+        // PWR_MGMT_1 register
+        void reset();
+        bool getSleepEnabled();
+        void setSleepEnabled(bool enabled);
+        bool getWakeCycleEnabled();
+        void setWakeCycleEnabled(bool enabled);
+        bool getTempSensorEnabled();
+        void setTempSensorEnabled(bool enabled);
+        uint8_t getClockSource();
+        void setClockSource(uint8_t source);
+
+        // PWR_MGMT_2 register
+        uint8_t getWakeFrequency();
+        void setWakeFrequency(uint8_t frequency);
+        bool getStandbyXAccelEnabled();
+        void setStandbyXAccelEnabled(bool enabled);
+        bool getStandbyYAccelEnabled();
+        void setStandbyYAccelEnabled(bool enabled);
+        bool getStandbyZAccelEnabled();
+        void setStandbyZAccelEnabled(bool enabled);
+        bool getStandbyXGyroEnabled();
+        void setStandbyXGyroEnabled(bool enabled);
+        bool getStandbyYGyroEnabled();
+        void setStandbyYGyroEnabled(bool enabled);
+        bool getStandbyZGyroEnabled();
+        void setStandbyZGyroEnabled(bool enabled);
+
+        // FIFO_COUNT_* registers
+        uint16_t getFIFOCount();
+
+        // FIFO_R_W register
+        uint8_t getFIFOByte();
+        void setFIFOByte(uint8_t data);
+        void getFIFOBytes(uint8_t *data, uint8_t length);
+
+        // WHO_AM_I register
+        uint8_t getDeviceID();
+        void setDeviceID(uint8_t id);
+        
+        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+        
+        // XG_OFFS_TC register
+        uint8_t getOTPBankValid();
+        void setOTPBankValid(bool enabled);
+        int8_t getXGyroOffsetTC();
+        void setXGyroOffsetTC(int8_t offset);
+
+        // YG_OFFS_TC register
+        int8_t getYGyroOffsetTC();
+        void setYGyroOffsetTC(int8_t offset);
+
+        // ZG_OFFS_TC register
+        int8_t getZGyroOffsetTC();
+        void setZGyroOffsetTC(int8_t offset);
+
+        // X_FINE_GAIN register
+        int8_t getXFineGain();
+        void setXFineGain(int8_t gain);
+
+        // Y_FINE_GAIN register
+        int8_t getYFineGain();
+        void setYFineGain(int8_t gain);
+
+        // Z_FINE_GAIN register
+        int8_t getZFineGain();
+        void setZFineGain(int8_t gain);
+
+        // XA_OFFS_* registers
+        int16_t getXAccelOffset();
+        void setXAccelOffset(int16_t offset);
+
+        // YA_OFFS_* register
+        int16_t getYAccelOffset();
+        void setYAccelOffset(int16_t offset);
+
+        // ZA_OFFS_* register
+        int16_t getZAccelOffset();
+        void setZAccelOffset(int16_t offset);
+
+        // XG_OFFS_USR* registers
+        int16_t getXGyroOffset();
+        void setXGyroOffset(int16_t offset);
+
+        // YG_OFFS_USR* register
+        int16_t getYGyroOffset();
+        void setYGyroOffset(int16_t offset);
+
+        // ZG_OFFS_USR* register
+        int16_t getZGyroOffset();
+        void setZGyroOffset(int16_t offset);
+        
+        // INT_ENABLE register (DMP functions)
+        bool getIntPLLReadyEnabled();
+        void setIntPLLReadyEnabled(bool enabled);
+        bool getIntDMPEnabled();
+        void setIntDMPEnabled(bool enabled);
+        
+        // DMP_INT_STATUS
+        bool getDMPInt5Status();
+        bool getDMPInt4Status();
+        bool getDMPInt3Status();
+        bool getDMPInt2Status();
+        bool getDMPInt1Status();
+        bool getDMPInt0Status();
+
+        // INT_STATUS register (DMP functions)
+        bool getIntPLLReadyStatus();
+        bool getIntDMPStatus();
+        
+        // USER_CTRL register (DMP functions)
+        bool getDMPEnabled();
+        void setDMPEnabled(bool enabled);
+        void resetDMP();
+        
+        // BANK_SEL register
+        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+        
+        // MEM_START_ADDR register
+        void setMemoryStartAddress(uint8_t address);
+        
+        // MEM_R_W register
+        uint8_t readMemoryByte();
+        void writeMemoryByte(uint8_t data);
+        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+        // DMP_CFG_1 register
+        uint8_t getDMPConfig1();
+        void setDMPConfig1(uint8_t config);
+
+        // DMP_CFG_2 register
+        uint8_t getDMPConfig2();
+        void setDMPConfig2(uint8_t config);
+
+        // special methods for MotionApps 2.0 implementation
+        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS20
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+        // special methods for MotionApps 4.1 implementation
+        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS41
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[14];
+};
+
+#endif /* _MPU9150_H_ */
diff --git a/firmware/lib/imu/MPU9250.cpp b/firmware/lib/imu/MPU9250.cpp
new file mode 100644
index 0000000..f67e055
--- /dev/null
+++ b/firmware/lib/imu/MPU9250.cpp
@@ -0,0 +1,3170 @@
+// I2Cdev library collection - MPU9250 I2C device class
+// Based on InvenSense MPU-9250 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 8/24/2011 by Jeff Rowberg 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#include "MPU9250.h"
+
+/** Default constructor, uses default I2C address.
+ * @see MPU9250_DEFAULT_ADDRESS
+ */
+MPU9250::MPU9250() {
+    devAddr = MPU9250_DEFAULT_ADDRESS;
+}
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see MPU9250_DEFAULT_ADDRESS
+ * @see MPU9250_ADDRESS_AD0_LOW
+ * @see MPU9250_ADDRESS_AD0_HIGH
+ */
+MPU9250::MPU9250(uint8_t address) {
+    devAddr = address;
+}
+
+/** Power on and prepare for general usage.
+ * This will activate the device and take it out of sleep mode (which must be done
+ * after start-up). This function also sets both the accelerometer and the gyroscope
+ * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets
+ * the clock source to use the X Gyro for reference, which is slightly better than
+ * the default internal clock source.
+ */
+void MPU9250::initialize() {
+    setClockSource(MPU9250_CLOCK_PLL_XGYRO);
+    setFullScaleGyroRange(MPU9250_GYRO_FS_250);
+    setFullScaleAccelRange(MPU9250_ACCEL_FS_2);
+    setSleepEnabled(false); // thanks to Jack Elston for pointing this one out!
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool MPU9250::testConnection() {
+    uint8_t device_id = getDeviceID();
+
+    if(device_id == 0x38 || device_id == 0x71)
+        return true;
+    else 
+        return false;
+}
+
+// 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 MPU9250::getAuxVDDIOLevel() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_YG_OFFS_TC, MPU9250_TC_PWR_MODE_BIT, buffer);
+    return buffer[0];
+}
+/** Set the auxiliary I2C supply voltage level.
+ * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to
+ * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to
+ * the MPU-6000, which does not have a VLOGIC pin.
+ * @param level I2C supply voltage level (0=VLOGIC, 1=VDD)
+ */
+void MPU9250::setAuxVDDIOLevel(uint8_t level) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_YG_OFFS_TC, MPU9250_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-9250 Product Specification document.
+ *
+ * @return Current sample rate
+ * @see MPU9250_RA_SMPLRT_DIV
+ */
+uint8_t MPU9250::getRate() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_SMPLRT_DIV, buffer);
+    return buffer[0];
+}
+/** Set gyroscope sample rate divider.
+ * @param rate New sample rate divider
+ * @see getRate()
+ * @see MPU9250_RA_SMPLRT_DIV
+ */
+void MPU9250::setRate(uint8_t rate) {
+    I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250::getExternalFrameSync() { + I2Cdev::readBits(devAddr, MPU9250_RA_CONFIG, MPU9250_CFG_EXT_SYNC_SET_BIT, MPU9250_CFG_EXT_SYNC_SET_LENGTH, buffer); + return buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see MPU9250_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void MPU9250::setExternalFrameSync(uint8_t sync) { + I2Cdev::writeBits(devAddr, MPU9250_RA_CONFIG, MPU9250_CFG_EXT_SYNC_SET_BIT, MPU9250_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 MPU9250_RA_CONFIG + * @see MPU9250_CFG_DLPF_CFG_BIT + * @see MPU9250_CFG_DLPF_CFG_LENGTH + */ +uint8_t MPU9250::getDLPFMode() { + I2Cdev::readBits(devAddr, MPU9250_RA_CONFIG, MPU9250_CFG_DLPF_CFG_BIT, MPU9250_CFG_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see MPU9250_DLPF_BW_256 + * @see MPU9250_RA_CONFIG + * @see MPU9250_CFG_DLPF_CFG_BIT + * @see MPU9250_CFG_DLPF_CFG_LENGTH + */ +void MPU9250::setDLPFMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, MPU9250_RA_CONFIG, MPU9250_CFG_DLPF_CFG_BIT, MPU9250_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 MPU9250_GYRO_FS_250 + * @see MPU9250_RA_GYRO_CONFIG + * @see MPU9250_GCONFIG_FS_SEL_BIT + * @see MPU9250_GCONFIG_FS_SEL_LENGTH + */ +uint8_t MPU9250::getFullScaleGyroRange() { + I2Cdev::readBits(devAddr, MPU9250_RA_GYRO_CONFIG, MPU9250_GCONFIG_FS_SEL_BIT, MPU9250_GCONFIG_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see MPU9250_GYRO_FS_250 + * @see MPU9250_RA_GYRO_CONFIG + * @see MPU9250_GCONFIG_FS_SEL_BIT + * @see MPU9250_GCONFIG_FS_SEL_LENGTH + */ +void MPU9250::setFullScaleGyroRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9250_RA_GYRO_CONFIG, MPU9250_GCONFIG_FS_SEL_BIT, MPU9250_GCONFIG_FS_SEL_LENGTH, range); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +bool MPU9250::getAccelXSelfTest() { + I2Cdev::readBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_XA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +void MPU9250::setAccelXSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +bool MPU9250::getAccelYSelfTest() { + I2Cdev::readBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_YA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +void MPU9250::setAccelYSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +bool MPU9250::getAccelZSelfTest() { + I2Cdev::readBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_ZA_ST_BIT, buffer); + return buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see MPU9250_RA_ACCEL_CONFIG + */ +void MPU9250::setAccelZSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_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 MPU9250_ACCEL_FS_2 + * @see MPU9250_RA_ACCEL_CONFIG + * @see MPU9250_ACONFIG_AFS_SEL_BIT + * @see MPU9250_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t MPU9250::getFullScaleAccelRange() { + I2Cdev::readBits(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_AFS_SEL_BIT, MPU9250_ACONFIG_AFS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void MPU9250::setFullScaleAccelRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_AFS_SEL_BIT, MPU9250_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-9250 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 MPU9250_DHPF_RESET + * @see MPU9250_RA_ACCEL_CONFIG + */ +uint8_t MPU9250::getDHPFMode() { + I2Cdev::readBits(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_ACCEL_HPF_BIT, MPU9250_ACONFIG_ACCEL_HPF_LENGTH, buffer); + return buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see MPU9250_DHPF_RESET + * @see MPU9250_RA_ACCEL_CONFIG + */ +void MPU9250::setDHPFMode(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, MPU9250_RA_ACCEL_CONFIG, MPU9250_ACONFIG_ACCEL_HPF_BIT, MPU9250_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-9250 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current free-fall acceleration threshold value (LSB = 2mg) + * @see MPU9250_RA_FF_THR + */ +uint8_t MPU9250::getFreefallDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9250_RA_FF_THR, buffer); + return buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see MPU9250_RA_FF_THR + */ +void MPU9250::setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9250_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-9250 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current free-fall duration threshold value (LSB = 1ms) + * @see MPU9250_RA_FF_DUR + */ +uint8_t MPU9250::getFreefallDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9250_RA_FF_DUR, buffer); + return buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see MPU9250_RA_FF_DUR + */ +void MPU9250::setFreefallDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9250_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-9250 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9250_RA_MOT_THR + */ +uint8_t MPU9250::getMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9250_RA_MOT_THR, buffer); + return buffer[0]; +} +/** Set free-fall event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see MPU9250_RA_MOT_THR + */ +void MPU9250::setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9250_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-9250 Product Specification document. + * + * @return Current motion detection duration threshold value (LSB = 1ms) + * @see MPU9250_RA_MOT_DUR + */ +uint8_t MPU9250::getMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9250_RA_MOT_DUR, buffer); + return buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see MPU9250_RA_MOT_DUR + */ +void MPU9250::setMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9250_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-9250 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9250_RA_ZRMOT_THR + */ +uint8_t MPU9250::getZeroMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9250_RA_ZRMOT_THR, buffer); + return buffer[0]; +} +/** Set zero motion detection event acceleration threshold. + * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) + * @see getZeroMotionDetectionThreshold() + * @see MPU9250_RA_ZRMOT_THR + */ +void MPU9250::setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9250_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-9250 Product Specification document, as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection duration threshold value (LSB = 64ms) + * @see MPU9250_RA_ZRMOT_DUR + */ +uint8_t MPU9250::getZeroMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9250_RA_ZRMOT_DUR, buffer); + return buffer[0]; +} +/** Set zero motion detection event duration threshold. + * @param duration New zero motion detection duration threshold value (LSB = 1ms) + * @see getZeroMotionDetectionDuration() + * @see MPU9250_RA_ZRMOT_DUR + */ +void MPU9250::setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9250_RA_ZRMOT_DUR, duration); +} + +// FIFO_EN register + +/** Get temperature FIFO enabled value. + * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and + * 66) to be written into the FIFO buffer. + * @return Current temperature FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getTempFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_TEMP_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setTempFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_TEMP_FIFO_EN_BIT, enabled); +} +/** Get gyroscope X-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and + * 68) to be written into the FIFO buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getXGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_XG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setXGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_XG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Y-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and + * 70) to be written into the FIFO buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getYGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_YG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setYGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_YG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Z-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and + * 72) to be written into the FIFO buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getZGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_ZG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setZGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_ZG_FIFO_EN_BIT, enabled); +} +/** Get accelerometer FIFO enabled value. + * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, + * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be + * written into the FIFO buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_ACCEL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_ACCEL_FIFO_EN_BIT, enabled); +} +/** Get Slave 2 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 2 to be written into the FIFO buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getSlave2FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_SLV2_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setSlave2FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_SLV2_FIFO_EN_BIT, enabled); +} +/** Get Slave 1 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 1 to be written into the FIFO buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getSlave1FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_SLV1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setSlave1FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_SLV1_FIFO_EN_BIT, enabled); +} +/** Get Slave 0 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 0 to be written into the FIFO buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU9250_RA_FIFO_EN + */ +bool MPU9250::getSlave0FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_SLV0_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see MPU9250_RA_FIFO_EN + */ +void MPU9250::setSlave0FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_FIFO_EN, MPU9250_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 MPU9250_RA_I2C_MST_CTRL + */ +bool MPU9250::getMultiMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_MULT_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see MPU9250_RA_I2C_MST_CTRL + */ +void MPU9250::setMultiMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_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 MPU9250_RA_I2C_MST_CTRL + */ +bool MPU9250::getWaitForExternalSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_WAIT_FOR_ES_BIT, buffer); + return buffer[0]; +} +/** Set wait-for-external-sensor-data enabled value. + * @param enabled New wait-for-external-sensor-data enabled value + * @see getWaitForExternalSensorEnabled() + * @see MPU9250_RA_I2C_MST_CTRL + */ +void MPU9250::setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_WAIT_FOR_ES_BIT, enabled); +} +/** Get Slave 3 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 3 to be written into the FIFO buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU9250_RA_MST_CTRL + */ +bool MPU9250::getSlave3FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_SLV_3_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see MPU9250_RA_MST_CTRL + */ +void MPU9250::setSlave3FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_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 MPU9250_RA_I2C_MST_CTRL + */ +bool MPU9250::getSlaveReadWriteTransitionEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_I2C_MST_P_NSR_BIT, buffer); + return buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see MPU9250_RA_I2C_MST_CTRL + */ +void MPU9250::setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_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 MPU9250_RA_I2C_MST_CTRL + */ +uint8_t MPU9250::getMasterClockSpeed() { + I2Cdev::readBits(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_I2C_MST_CLK_BIT, MPU9250_I2C_MST_CLK_LENGTH, buffer); + return buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see MPU9250_RA_I2C_MST_CTRL + */ +void MPU9250::setMasterClockSpeed(uint8_t speed) { + I2Cdev::writeBits(devAddr, MPU9250_RA_I2C_MST_CTRL, MPU9250_I2C_MST_CLK_BIT, MPU9250_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-9250 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 MPU9250_RA_I2C_SLV0_ADDR + */ +uint8_t MPU9250::getSlaveAddress(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9250_RA_I2C_SLV0_ADDR + num*3, buffer); + return buffer[0]; +} +/** Set the I2C address of the specified slave (0-3). + * @param num Slave number (0-3) + * @param address New address for specified slave + * @see getSlaveAddress() + * @see MPU9250_RA_I2C_SLV0_ADDR + */ +void MPU9250::setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9250_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-9250 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 MPU9250_RA_I2C_SLV0_REG + */ +uint8_t MPU9250::getSlaveRegister(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9250_RA_I2C_SLV0_REG + num*3, buffer); + return buffer[0]; +} +/** Set the active internal register for the specified slave (0-3). + * @param num Slave number (0-3) + * @param reg New active register for specified slave + * @see getSlaveRegister() + * @see MPU9250_RA_I2C_SLV0_REG + */ +void MPU9250::setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_I2C_SLV0_CTRL + */ +bool MPU9250::getSlaveEnabled(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New enabled value for specified slave + * @see getSlaveEnabled() + * @see MPU9250_RA_I2C_SLV0_CTRL + */ +void MPU9250::setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_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 MPU9250_RA_I2C_SLV0_CTRL + */ +bool MPU9250::getSlaveWordByteSwap(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_BYTE_SW_BIT, buffer); + return buffer[0]; +} +/** Set word pair byte-swapping enabled for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair byte-swapping enabled value for specified slave + * @see getSlaveWordByteSwap() + * @see MPU9250_RA_I2C_SLV0_CTRL + */ +void MPU9250::setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_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 MPU9250_RA_I2C_SLV0_CTRL + */ +bool MPU9250::getSlaveWriteMode(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the specified slave (0-3). + * @param num Slave number (0-3) + * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) + * @see getSlaveWriteMode() + * @see MPU9250_RA_I2C_SLV0_CTRL + */ +void MPU9250::setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_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 MPU9250_RA_I2C_SLV0_CTRL + */ +bool MPU9250::getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_GRP_BIT, buffer); + return buffer[0]; +} +/** Set word pair grouping order offset for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair grouping order offset for specified slave + * @see getSlaveWordGroupOffset() + * @see MPU9250_RA_I2C_SLV0_CTRL + */ +void MPU9250::setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_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 MPU9250_RA_I2C_SLV0_CTRL + */ +uint8_t MPU9250::getSlaveDataLength(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBits(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_LEN_BIT, MPU9250_I2C_SLV_LEN_LENGTH, buffer); + return buffer[0]; +} +/** Set number of bytes to read for the specified slave (0-3). + * @param num Slave number (0-3) + * @param length Number of bytes to read for specified slave + * @see getSlaveDataLength() + * @see MPU9250_RA_I2C_SLV0_CTRL + */ +void MPU9250::setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) return; + I2Cdev::writeBits(devAddr, MPU9250_RA_I2C_SLV0_CTRL + num*3, MPU9250_I2C_SLV_LEN_BIT, MPU9250_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 MPU9250_RA_I2C_SLV4_ADDR + */ +uint8_t MPU9250::getSlave4Address() { + I2Cdev::readByte(devAddr, MPU9250_RA_I2C_SLV4_ADDR, buffer); + return buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see MPU9250_RA_I2C_SLV4_ADDR + */ +void MPU9250::setSlave4Address(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_I2C_SLV4_REG + */ +uint8_t MPU9250::getSlave4Register() { + I2Cdev::readByte(devAddr, MPU9250_RA_I2C_SLV4_REG, buffer); + return buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see MPU9250_RA_I2C_SLV4_REG + */ +void MPU9250::setSlave4Register(uint8_t reg) { + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_I2C_SLV4_DO + */ +void MPU9250::setSlave4OutputByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_I2C_SLV4_CTRL + */ +bool MPU9250::getSlave4Enabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_I2C_SLV4_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see MPU9250_RA_I2C_SLV4_CTRL + */ +void MPU9250::setSlave4Enabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_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 MPU9250_RA_I2C_SLV4_CTRL + */ +bool MPU9250::getSlave4InterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_I2C_SLV4_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4 transaction interrupts. + * @param enabled New enabled value for Slave 4 transaction interrupts. + * @see getSlave4InterruptEnabled() + * @see MPU9250_RA_I2C_SLV4_CTRL + */ +void MPU9250::setSlave4InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_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 MPU9250_RA_I2C_SLV4_CTRL + */ +bool MPU9250::getSlave4WriteMode() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_I2C_SLV4_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the Slave 4. + * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see getSlave4WriteMode() + * @see MPU9250_RA_I2C_SLV4_CTRL + */ +void MPU9250::setSlave4WriteMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_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 MPU9250_RA_I2C_SLV4_CTRL + */ +uint8_t MPU9250::getSlave4MasterDelay() { + I2Cdev::readBits(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_I2C_SLV4_MST_DLY_BIT, MPU9250_I2C_SLV4_MST_DLY_LENGTH, buffer); + return buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see MPU9250_RA_I2C_SLV4_CTRL + */ +void MPU9250::setSlave4MasterDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9250_RA_I2C_SLV4_CTRL, MPU9250_I2C_SLV4_MST_DLY_BIT, MPU9250_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 MPU9250_RA_I2C_SLV4_DI + */ +uint8_t MPU9250::getSlate4InputByte() { + I2Cdev::readByte(devAddr, MPU9250_RA_I2C_SLV4_DI, buffer); + return buffer[0]; +} + +// I2C_MST_STATUS register + +/** Get FSYNC interrupt status. + * This bit reflects the status of the FSYNC interrupt from an external device + * into the MPU-60X0. This is used as a way to pass an external interrupt + * through the MPU-60X0 to the host application processor. When set to 1, this + * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG + * (Register 55). + * @return FSYNC interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getPassthroughStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_PASS_THROUGH_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 transaction done status. + * Automatically sets to 1 when a Slave 4 transaction has completed. This + * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register + * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the + * I2C_SLV4_CTRL register (Register 52). + * @return Slave 4 transaction done status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave4IsDone() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV4_DONE_BIT, buffer); + return buffer[0]; +} +/** Get master arbitration lost status. + * This bit automatically sets to 1 when the I2C Master has lost arbitration of + * the auxiliary I2C bus (an error condition). This triggers an interrupt if the + * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. + * @return Master arbitration lost status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getLostArbitration() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_LOST_ARB_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 4 NACK interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave4Nack() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV4_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 3 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 3 NACK interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave3Nack() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV3_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 2 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 2 NACK interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave2Nack() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV2_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 1 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 1 NACK interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave1Nack() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV1_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 0 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 0 NACK interrupt status + * @see MPU9250_RA_I2C_MST_STATUS + */ +bool MPU9250::getSlave0Nack() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_STATUS, MPU9250_MST_I2C_SLV0_NACK_BIT, buffer); + return buffer[0]; +} + +// INT_PIN_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_LEVEL_BIT + */ +bool MPU9250::getInterruptMode() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_LEVEL_BIT + */ +void MPU9250::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_OPEN_BIT + */ +bool MPU9250::getInterruptDrive() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_INT_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_OPEN_BIT + */ +void MPU9250::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_LATCH_INT_EN_BIT + */ +bool MPU9250::getInterruptLatch() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_LATCH_INT_EN_BIT + */ +void MPU9250::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_RD_CLEAR_BIT + */ +bool MPU9250::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_INT_RD_CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_INT_RD_CLEAR_BIT + */ +void MPU9250::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool MPU9250::getFSyncInterruptLevel() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC interrupt logic level mode. + * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void MPU9250::setFSyncInterruptLevel(bool level) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_FSYNC_INT_EN_BIT + */ +bool MPU9250::getFSyncInterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_FSYNC_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_FSYNC_INT_EN_BIT + */ +void MPU9250::setFSyncInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_I2C_BYPASS_EN_BIT + */ +bool MPU9250::getI2CBypassEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_I2C_BYPASS_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @param enabled New I2C bypass enabled status + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_I2C_BYPASS_EN_BIT + */ +void MPU9250::setI2CBypassEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_CLKOUT_EN_BIT + */ +bool MPU9250::getClockOutputEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_INTCFG_CLKOUT_EN_BIT, buffer); + return buffer[0]; +} +/** Set reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @param enabled New reference clock output enabled status + * @see MPU9250_RA_INT_PIN_CFG + * @see MPU9250_INTCFG_CLKOUT_EN_BIT + */ +void MPU9250::setClockOutputEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_PIN_CFG, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FF_BIT + **/ +uint8_t MPU9250::getIntEnabled() { + I2Cdev::readByte(devAddr, MPU9250_RA_INT_ENABLE, buffer); + return buffer[0]; +} +/** Set full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit should be + * set 0 for disabled, 1 for enabled. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FF_BIT + **/ +void MPU9250::setIntEnabled(uint8_t enabled) { + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FF_BIT + **/ +bool MPU9250::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FF_BIT + **/ +void MPU9250::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_MOT_BIT + **/ +bool MPU9250::getIntMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_MOT_BIT + **/ +void MPU9250::setIntMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_ZMOT_BIT + **/ +bool MPU9250::getIntZeroMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_ZMOT_BIT + **/ +void MPU9250::setIntZeroMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool MPU9250::getIntFIFOBufferOverflowEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_FIFO_OFLOW_BIT + **/ +void MPU9250::setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_I2C_MST_INT_BIT + **/ +bool MPU9250::getIntI2CMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_I2C_MST_INT_BIT + **/ +void MPU9250::setIntI2CMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_ENABLE + * @see MPU9250_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9250::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see MPU9250_RA_INT_CFG + * @see MPU9250_INTERRUPT_DATA_RDY_BIT + */ +void MPU9250::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_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 MPU9250_RA_INT_STATUS + */ +uint8_t MPU9250::getIntStatus() { + I2Cdev::readByte(devAddr, MPU9250_RA_INT_STATUS, buffer); + return buffer[0]; +} +/** Get Free Fall interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_FF_BIT + */ +bool MPU9250::getIntFreefallStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Get Motion Detection interrupt status. + * This bit automatically sets to 1 when a Motion Detection interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_MOT_BIT + */ +bool MPU9250::getIntMotionStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Get Zero Motion Detection interrupt status. + * This bit automatically sets to 1 when a Zero Motion Detection interrupt has + * been generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_ZMOT_BIT + */ +bool MPU9250::getIntZeroMotionStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Get FIFO Buffer Overflow interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_FIFO_OFLOW_BIT + */ +bool MPU9250::getIntFIFOBufferOverflowStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Get I2C Master interrupt status. + * This bit automatically sets to 1 when an I2C Master interrupt has been + * generated. For a list of I2C Master interrupts, please refer to Register 54. + * The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_I2C_MST_INT_BIT + */ +bool MPU9250::getIntI2CMasterStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * This bit automatically sets to 1 when a Data Ready interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9250_RA_INT_STATUS + * @see MPU9250_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9250::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} + +// ACCEL_*OUT_* registers + +/** Get raw 9-axis motion sensor readings (accel/gyro/compass). + * FUNCTION NOT FULLY IMPLEMENTED YET. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @param mx 16-bit signed integer container for magnetometer X-axis value + * @param my 16-bit signed integer container for magnetometer Y-axis value + * @param mz 16-bit signed integer container for magnetometer Z-axis value + * @see getMotion6() + * @see getAcceleration() + * @see getRotation() + * @see MPU9250_RA_ACCEL_XOUT_H + */ +void MPU9250::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) { + + //get accel and gyro + getMotion6(ax, ay, az, gx, gy, gz); + + //read mag + I2Cdev::writeByte(devAddr, MPU9250_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer + delay(10); + I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer + delay(10); + I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); + *mx = (((int16_t)buffer[1]) << 8) | buffer[0]; + *my = (((int16_t)buffer[3]) << 8) | buffer[2]; + *mz = (((int16_t)buffer[5]) << 8) | buffer[4]; +} +/** 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 MPU9250_RA_ACCEL_XOUT_H + */ +void MPU9250::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { + I2Cdev::readBytes(devAddr, MPU9250_RA_ACCEL_XOUT_H, 14, buffer); + *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; + *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; + *az = (((int16_t)buffer[4]) << 8) | buffer[5]; + *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; + *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; + *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; +} +/** Get 3-axis accelerometer readings. + * These registers store the most recent accelerometer measurements. + * Accelerometer measurements are written to these registers at the Sample Rate + * as defined in Register 25. + * + * The accelerometer measurement registers, along with the temperature + * measurement registers, gyroscope measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * + * The data within the accelerometer sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS + * (Register 28). For each full scale setting, the accelerometers' sensitivity + * per LSB in ACCEL_xOUT is shown in the table below: + * + *
+ * 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 MPU9250_RA_GYRO_XOUT_H + */ +void MPU9250::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9250_RA_ACCEL_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_ACCEL_XOUT_H + */ +int16_t MPU9250::getAccelerationX() { + I2Cdev::readBytes(devAddr, MPU9250_RA_ACCEL_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_ACCEL_YOUT_H + */ +int16_t MPU9250::getAccelerationY() { + I2Cdev::readBytes(devAddr, MPU9250_RA_ACCEL_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_ACCEL_ZOUT_H + */ +int16_t MPU9250::getAccelerationZ() { + I2Cdev::readBytes(devAddr, MPU9250_RA_ACCEL_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see MPU9250_RA_TEMP_OUT_H + */ +int16_t MPU9250::getTemperature() { + I2Cdev::readBytes(devAddr, MPU9250_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +void MPU9250::getHeading(int16_t* mx, int16_t* my, int16_t* mz) { + //read mag + I2Cdev::writeByte(devAddr, MPU9250_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer + delay(10); + I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer + delay(10); + I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); + *mx = (((int16_t)buffer[1]) << 8) | buffer[0]; + *my = (((int16_t)buffer[3]) << 8) | buffer[2]; + *mz = (((int16_t)buffer[5]) << 8) | buffer[4]; +} + +// 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 MPU9250_RA_GYRO_XOUT_H + */ +void MPU9250::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9250_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_GYRO_XOUT_H + */ +int16_t MPU9250::getRotationX() { + I2Cdev::readBytes(devAddr, MPU9250_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_GYRO_YOUT_H + */ +int16_t MPU9250::getRotationY() { + I2Cdev::readBytes(devAddr, MPU9250_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9250_RA_GYRO_ZOUT_H + */ +int16_t MPU9250::getRotationZ() { + I2Cdev::readBytes(devAddr, MPU9250_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// EXT_SENS_DATA_* registers + +/** Read single byte from external sensor data register. + * These registers store data read from external sensors by the Slave 0, 1, 2, + * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in + * I2C_SLV4_DI (Register 53). + * + * External sensor data is written to these registers at the Sample Rate as + * defined in Register 25. This access rate can be reduced by using the Slave + * Delay Enable registers (Register 103). + * + * External sensor data registers, along with the gyroscope measurement + * registers, accelerometer measurement registers, and temperature measurement + * registers, are composed of two sets of registers: an internal register set + * and a user-facing read register set. + * + * The data within the external sensors' internal register set is always updated + * at the Sample Rate (or the reduced access rate) whenever the serial interface + * is idle. This guarantees that a burst read of sensor registers will read + * measurements from the same sampling instant. Note that if burst reads are not + * used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Data is placed in these external sensor data registers according to + * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, + * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from + * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as + * defined in Register 25) or delayed rate (if specified in Register 52 and + * 103). During each Sample cycle, slave reads are performed in order of Slave + * number. If all slaves are enabled with more than zero bytes to be read, the + * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. + * + * Each enabled slave will have EXT_SENS_DATA registers associated with it by + * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from + * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may + * change the higher numbered slaves' associated registers. Furthermore, if + * fewer total bytes are being read from the external sensors as a result of + * such a change, then the data remaining in the registers which no longer have + * an associated slave device (i.e. high numbered registers) will remain in + * these previously allocated registers unless reset. + * + * If the sum of the read lengths of all SLVx transactions exceed the number of + * available EXT_SENS_DATA registers, the excess bytes will be dropped. There + * are 24 EXT_SENS_DATA registers and hence the total read lengths between all + * the slaves cannot be greater than 24 or some bytes will be lost. + * + * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further + * information regarding the characteristics of Slave 4, please refer to + * Registers 49 to 53. + * + * EXAMPLE: + * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and + * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that + * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 + * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 + * will be associated with Slave 1. If Slave 2 is enabled as well, registers + * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. + * + * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then + * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 + * instead. + * + * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: + * If a slave is disabled at any time, the space initially allocated to the + * slave in the EXT_SENS_DATA register, will remain associated with that slave. + * This is to avoid dynamic adjustment of the register allocation. + * + * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all + * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). + * + * This above is also true if one of the slaves gets NACKed and stops + * functioning. + * + * @param position Starting position (0-23) + * @return Byte read from register + */ +uint8_t MPU9250::getExternalSensorByte(int position) { + I2Cdev::readByte(devAddr, MPU9250_RA_EXT_SENS_DATA_00 + position, buffer); + return buffer[0]; +} +/** Read word (2 bytes) from external sensor data registers. + * @param position Starting position (0-21) + * @return Word read from register + * @see getExternalSensorByte() + */ +uint16_t MPU9250::getExternalSensorWord(int position) { + I2Cdev::readBytes(devAddr, MPU9250_RA_EXT_SENS_DATA_00 + position, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} +/** Read double word (4 bytes) from external sensor data registers. + * @param position Starting position (0-20) + * @return Double word read from registers + * @see getExternalSensorByte() + */ +uint32_t MPU9250::getExternalSensorDWord(int position) { + I2Cdev::readBytes(devAddr, MPU9250_RA_EXT_SENS_DATA_00 + position, 4, buffer); + return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; +} + +// MOT_DETECT_STATUS register + +/** Get X-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_XNEG_BIT + */ +bool MPU9250::getXNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_XNEG_BIT, buffer); + return buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_XPOS_BIT + */ +bool MPU9250::getXPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_XPOS_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_YNEG_BIT + */ +bool MPU9250::getYNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_YNEG_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_YPOS_BIT + */ +bool MPU9250::getYPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_YPOS_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_ZNEG_BIT + */ +bool MPU9250::getZNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_ZNEG_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_ZPOS_BIT + */ +bool MPU9250::getZPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_ZPOS_BIT, buffer); + return buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see MPU9250_RA_MOT_DETECT_STATUS + * @see MPU9250_MOTION_MOT_ZRMOT_BIT + */ +bool MPU9250::getZeroMotionDetected() { + I2Cdev::readBit(devAddr, MPU9250_RA_MOT_DETECT_STATUS, MPU9250_MOTION_MOT_ZRMOT_BIT, buffer); + return buffer[0]; +} + +// I2C_SLV*_DO register + +/** Write byte to Data Output container for specified slave. + * This register holds the output data written into Slave when Slave is set to + * write mode. For further information regarding Slave control, please + * refer to Registers 37 to 39 and immediately following. + * @param num Slave number (0-3) + * @param data Byte to write + * @see MPU9250_RA_I2C_SLV0_DO + */ +void MPU9250::setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_I2C_MST_DELAY_CTRL + * @see MPU9250_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool MPU9250::getExternalShadowDelayEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_DELAY_CTRL, MPU9250_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); + return buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see MPU9250_RA_I2C_MST_DELAY_CTRL + * @see MPU9250_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void MPU9250::setExternalShadowDelayEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_I2C_MST_DELAY_CTRL, MPU9250_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 MPU9250_RA_I2C_MST_DELAY_CTRL + * @see MPU9250_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool MPU9250::getSlaveDelayEnabled(uint8_t num) { + // MPU9250_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) return 0; + I2Cdev::readBit(devAddr, MPU9250_RA_I2C_MST_DELAY_CTRL, num, buffer); + return buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see MPU9250_RA_I2C_MST_DELAY_CTRL + * @see MPU9250_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void MPU9250::setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_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 MPU9250_RA_SIGNAL_PATH_RESET + * @see MPU9250_PATHRESET_GYRO_RESET_BIT + */ +void MPU9250::resetGyroscopePath() { + I2Cdev::writeBit(devAddr, MPU9250_RA_SIGNAL_PATH_RESET, MPU9250_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 MPU9250_RA_SIGNAL_PATH_RESET + * @see MPU9250_PATHRESET_ACCEL_RESET_BIT + */ +void MPU9250::resetAccelerometerPath() { + I2Cdev::writeBit(devAddr, MPU9250_RA_SIGNAL_PATH_RESET, MPU9250_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 MPU9250_RA_SIGNAL_PATH_RESET + * @see MPU9250_PATHRESET_TEMP_RESET_BIT + */ +void MPU9250::resetTemperaturePath() { + I2Cdev::writeBit(devAddr, MPU9250_RA_SIGNAL_PATH_RESET, MPU9250_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-9250 Product Specification document for + * further information regarding the detection modules. + * @return Current accelerometer power-on delay + * @see MPU9250_RA_MOT_DETECT_CTRL + * @see MPU9250_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t MPU9250::getAccelerometerPowerOnDelay() { + I2Cdev::readBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_ACCEL_ON_DELAY_BIT, MPU9250_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); + return buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see MPU9250_RA_MOT_DETECT_CTRL + * @see MPU9250_DETECT_ACCEL_ON_DELAY_BIT + */ +void MPU9250::setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_ACCEL_ON_DELAY_BIT, MPU9250_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 MPU9250_RA_MOT_DETECT_CTRL + * @see MPU9250_DETECT_FF_COUNT_BIT + */ +uint8_t MPU9250::getFreefallDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_FF_COUNT_BIT, MPU9250_DETECT_FF_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see MPU9250_RA_MOT_DETECT_CTRL + * @see MPU9250_DETECT_FF_COUNT_BIT + */ +void MPU9250::setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_FF_COUNT_BIT, MPU9250_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 MPU9250::getMotionDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_MOT_COUNT_BIT, MPU9250_DETECT_MOT_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see MPU9250_RA_MOT_DETECT_CTRL + * @see MPU9250_DETECT_MOT_COUNT_BIT + */ +void MPU9250::setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9250_RA_MOT_DETECT_CTRL, MPU9250_DETECT_MOT_COUNT_BIT, MPU9250_DETECT_MOT_COUNT_LENGTH, decrement); +} + +// USER_CTRL register + +/** Get FIFO enabled status. + * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer + * cannot be written to or read from while disabled. The FIFO buffer's state + * does not change unless the MPU-60X0 is power cycled. + * @return Current FIFO enabled status + * @see MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_FIFO_EN_BIT + */ +bool MPU9250::getFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_FIFO_EN_BIT + */ +void MPU9250::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_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 MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_I2C_MST_EN_BIT + */ +bool MPU9250::getI2CMasterModeEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_I2C_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_I2C_MST_EN_BIT + */ +void MPU9250::setI2CMasterModeEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_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 MPU9250::switchSPIEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This + * bit automatically clears to 0 after the reset has been triggered. + * @see MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_FIFO_RESET_BIT + */ +void MPU9250::resetFIFO() { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_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 MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_I2C_MST_RESET_BIT + */ +void MPU9250::resetI2CMaster() { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_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 MPU9250_RA_USER_CTRL + * @see MPU9250_USERCTRL_SIG_COND_RESET_BIT + */ +void MPU9250::resetSensors() { + I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_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 MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_DEVICE_RESET_BIT + */ +void MPU9250::reset() { + I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_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 MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_SLEEP_BIT + */ +bool MPU9250::getSleepEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_SLEEP_BIT + */ +void MPU9250::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_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 MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_CYCLE_BIT + */ +bool MPU9250::getWakeCycleEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_CYCLE_BIT, buffer); + return buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_CYCLE_BIT + */ +void MPU9250::setWakeCycleEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_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 MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_TEMP_DIS_BIT + */ +bool MPU9250::getTempSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_TEMP_DIS_BIT, buffer); + return buffer[0] == 0; // 1 is actually disabled here +} +/** Set temperature sensor enabled status. + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @param enabled New temperature sensor enabled status + * @see getTempSensorEnabled() + * @see MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_TEMP_DIS_BIT + */ +void MPU9250::setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_CLKSEL_BIT + * @see MPU9250_PWR1_CLKSEL_LENGTH + */ +uint8_t MPU9250::getClockSource() { + I2Cdev::readBits(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_CLKSEL_BIT, MPU9250_PWR1_CLKSEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * An internal 8MHz oscillator, gyroscope based clock, or external sources can + * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator + * or an external source is chosen as the clock source, the MPU-60X0 can operate + * in low power modes with the gyroscopes disabled. + * + * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. + * However, it is highly recommended that the device be configured to use one of + * the gyroscopes (or an external clock source) as the clock reference for + * improved stability. The clock source can be selected according to the following table: + * + *
+ * 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 MPU9250_RA_PWR_MGMT_1 + * @see MPU9250_PWR1_CLKSEL_BIT + * @see MPU9250_PWR1_CLKSEL_LENGTH + */ +void MPU9250::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, MPU9250_RA_PWR_MGMT_1, MPU9250_PWR1_CLKSEL_BIT, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ */
+uint8_t MPU9250::getWakeFrequency() {
+    I2Cdev::readBits(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_LP_WAKE_CTRL_BIT, MPU9250_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU9250_RA_PWR_MGMT_2
+ */
+void MPU9250::setWakeFrequency(uint8_t frequency) {
+    I2Cdev::writeBits(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_LP_WAKE_CTRL_BIT, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_XA_BIT
+ */
+bool MPU9250::getStandbyXAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_XA_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_XA_BIT
+ */
+void MPU9250::setStandbyXAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_YA_BIT
+ */
+bool MPU9250::getStandbyYAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_YA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_YA_BIT
+ */
+void MPU9250::setStandbyYAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_ZA_BIT
+ */
+bool MPU9250::getStandbyZAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_ZA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_ZA_BIT
+ */
+void MPU9250::setStandbyZAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_XG_BIT
+ */
+bool MPU9250::getStandbyXGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_XG_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_XG_BIT
+ */
+void MPU9250::setStandbyXGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_YG_BIT
+ */
+bool MPU9250::getStandbyYGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_YG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_YG_BIT
+ */
+void MPU9250::setStandbyYGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_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 MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_ZG_BIT
+ */
+bool MPU9250::getStandbyZGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_ZG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU9250_RA_PWR_MGMT_2
+ * @see MPU9250_PWR2_STBY_ZG_BIT
+ */
+void MPU9250::setStandbyZGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_PWR_MGMT_2, MPU9250_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU9250::getFIFOCount() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_FIFO_COUNTH, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU9250::getFIFOByte() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_FIFO_R_W, buffer);
+    return buffer[0];
+}
+void MPU9250::getFIFOBytes(uint8_t *data, uint8_t length) {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU9250_RA_FIFO_R_W
+ */
+void MPU9250::setFIFOByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9250_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 MPU9250_RA_WHO_AM_I
+ * @see MPU9250_WHO_AM_I_BIT
+ * @see MPU9250_WHO_AM_I_LENGTH
+ */
+uint8_t MPU9250::getDeviceID() {
+    I2Cdev::readBits(devAddr, MPU9250_RA_WHO_AM_I, MPU9250_WHO_AM_I_BIT, MPU9250_WHO_AM_I_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU9250_RA_WHO_AM_I
+ * @see MPU9250_WHO_AM_I_BIT
+ * @see MPU9250_WHO_AM_I_LENGTH
+ */
+void MPU9250::setDeviceID(uint8_t id) {
+    I2Cdev::writeBits(devAddr, MPU9250_RA_WHO_AM_I, MPU9250_WHO_AM_I_BIT, MPU9250_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU9250::getOTPBankValid() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_XG_OFFS_TC, MPU9250_TC_OTP_BNK_VLD_BIT, buffer);
+    return buffer[0];
+}
+void MPU9250::setOTPBankValid(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_XG_OFFS_TC, MPU9250_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU9250::getXGyroOffset() {
+    I2Cdev::readBits(devAddr, MPU9250_RA_XG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9250::setXGyroOffset(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9250_RA_XG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU9250::getYGyroOffset() {
+    I2Cdev::readBits(devAddr, MPU9250_RA_YG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9250::setYGyroOffset(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9250_RA_YG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU9250::getZGyroOffset() {
+    I2Cdev::readBits(devAddr, MPU9250_RA_ZG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9250::setZGyroOffset(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9250_RA_ZG_OFFS_TC, MPU9250_TC_OFFSET_BIT, MPU9250_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU9250::getXFineGain() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_X_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9250::setXFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU9250::getYFineGain() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_Y_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9250::setYFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU9250::getZFineGain() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_Z_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9250::setZFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU9250::getXAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_XA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setXAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU9250::getYAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_YA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setYAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU9250::getZAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_ZA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setZAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU9250::getXGyroOffsetUser() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_XG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setXGyroOffsetUser(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU9250::getYGyroOffsetUser() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_YG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setYGyroOffsetUser(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU9250::getZGyroOffsetUser() {
+    I2Cdev::readBytes(devAddr, MPU9250_RA_ZG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9250::setZGyroOffsetUser(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9250_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU9250::getIntPLLReadyEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9250::setIntPLLReadyEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU9250::getIntDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9250::setIntDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_INT_ENABLE, MPU9250_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU9250::getDMPInt5Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_5_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getDMPInt4Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_4_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getDMPInt3Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_3_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getDMPInt2Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_2_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getDMPInt1Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_1_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getDMPInt0Status() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_DMP_INT_STATUS, MPU9250_DMPINT_0_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU9250::getIntPLLReadyStatus() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9250::getIntDMPStatus() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_INT_STATUS, MPU9250_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU9250::getDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_DMP_EN_BIT, buffer);
+    return buffer[0];
+}
+void MPU9250::setDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU9250::resetDMP() {
+    I2Cdev::writeBit(devAddr, MPU9250_RA_USER_CTRL, MPU9250_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU9250::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
+    bank &= 0x1F;
+    if (userBank) bank |= 0x20;
+    if (prefetchEnabled) bank |= 0x40;
+    I2Cdev::writeByte(devAddr, MPU9250_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU9250::setMemoryStartAddress(uint8_t address) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU9250::readMemoryByte() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_MEM_R_W, buffer);
+    return buffer[0];
+}
+void MPU9250::writeMemoryByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_MEM_R_W, data);
+}
+void MPU9250::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9250_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        // read the chunk of data as specified
+        I2Cdev::readBytes(devAddr, MPU9250_RA_MEM_R_W, chunkSize, data + i);
+        
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+}
+bool MPU9250::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer;
+    uint8_t *progBuffer;
+    uint16_t i;
+    uint8_t j;
+    if (verify) verifyBuffer = (uint8_t *)malloc(MPU9250_DMP_MEMORY_CHUNK_SIZE);
+    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU9250_DMP_MEMORY_CHUNK_SIZE);
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9250_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+        
+        if (useProgMem) {
+            // write the chunk of data as specified
+            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+        } else {
+            // write the chunk of data as specified
+            progBuffer = (uint8_t *)data + i;
+        }
+
+        I2Cdev::writeBytes(devAddr, MPU9250_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+            I2Cdev::readBytes(devAddr, MPU9250_RA_MEM_R_W, chunkSize, verifyBuffer);
+            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+                /*Serial.print("Block write verification error, bank ");
+                Serial.print(bank, DEC);
+                Serial.print(", address ");
+                Serial.print(address, DEC);
+                Serial.print("!\nExpected:");
+                for (j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (progBuffer[j] < 16) Serial.print("0");
+                    Serial.print(progBuffer[j], HEX);
+                }
+                Serial.print("\nReceived:");
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (verifyBuffer[i + j] < 16) Serial.print("0");
+                    Serial.print(verifyBuffer[i + j], HEX);
+                }
+                Serial.print("\n");*/
+                free(verifyBuffer);
+                if (useProgMem) free(progBuffer);
+                return false; // uh oh.
+            }
+        }
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+    if (verify) free(verifyBuffer);
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9250::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
+    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU9250::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
+    uint8_t *progBuffer, success, special;
+    uint16_t i, j;
+    if (useProgMem) {
+        progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+    }
+
+    // config set data is a long string of blocks with the following structure:
+    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+    uint8_t bank, offset, length;
+    for (i = 0; i < dataSize;) {
+        if (useProgMem) {
+            bank = pgm_read_byte(data + i++);
+            offset = pgm_read_byte(data + i++);
+            length = pgm_read_byte(data + i++);
+        } else {
+            bank = data[i++];
+            offset = data[i++];
+            length = data[i++];
+        }
+
+        // write data or perform special action
+        if (length > 0) {
+            // regular block of data to write
+            /*Serial.print("Writing config block to bank ");
+            Serial.print(bank);
+            Serial.print(", offset ");
+            Serial.print(offset);
+            Serial.print(", length=");
+            Serial.println(length);*/
+            if (useProgMem) {
+                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+            } else {
+                progBuffer = (uint8_t *)data + i;
+            }
+            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+            i += length;
+        } else {
+            // special instruction
+            // NOTE: this kind of behavior (what and when to do certain things)
+            // is totally undocumented. This code is in here based on observed
+            // behavior only, and exactly why (or even whether) it has to be here
+            // is anybody's guess for now.
+            if (useProgMem) {
+                special = pgm_read_byte(data + i++);
+            } else {
+                special = data[i++];
+            }
+            /*Serial.print("Special command code ");
+            Serial.print(special, HEX);
+            Serial.println(" found...");*/
+            if (special == 0x01) {
+                // enable DMP-related interrupts
+                
+                //setIntZeroMotionEnabled(true);
+                //setIntFIFOBufferOverflowEnabled(true);
+                //setIntDMPEnabled(true);
+                I2Cdev::writeByte(devAddr, MPU9250_RA_INT_ENABLE, 0x32);  // single operation
+
+                success = true;
+            } else {
+                // unknown special command
+                success = false;
+            }
+        }
+        
+        if (!success) {
+            if (useProgMem) free(progBuffer);
+            return false; // uh oh
+        }
+    }
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9250::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
+    return writeDMPConfigurationSet(data, dataSize, true);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU9250::getDMPConfig1() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_DMP_CFG_1, buffer);
+    return buffer[0];
+}
+void MPU9250::setDMPConfig1(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU9250::getDMPConfig2() {
+    I2Cdev::readByte(devAddr, MPU9250_RA_DMP_CFG_2, buffer);
+    return buffer[0];
+}
+void MPU9250::setDMPConfig2(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9250_RA_DMP_CFG_2, config);
+}
\ No newline at end of file
diff --git a/firmware/lib/imu/MPU9250.h b/firmware/lib/imu/MPU9250.h
new file mode 100644
index 0000000..e2601b1
--- /dev/null
+++ b/firmware/lib/imu/MPU9250.h
@@ -0,0 +1,1043 @@
+// I2Cdev library collection - MPU9250 I2C device class
+// Based on InvenSense MPU-9250 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2012 Jeff Rowberg
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+===============================================
+*/
+
+#ifndef _MPU9250_H_
+#define _MPU9250_H_
+
+#include "I2Cdev.h"
+
+// // Tom Carpenter's conditional PROGMEM code
+// // http://forum.arduino.cc/index.php?topic=129407.0
+// #ifdef __AVR__
+//     #include 
+// #else
+//     // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+//     #ifndef __PGMSPACE_H_
+//         #define __PGMSPACE_H_ 1
+//         #include 
+
+//         #define PROGMEM
+//         #define PGM_P  const char *
+//         #define PSTR(str) (str)
+//         #define F(x) x
+
+//         typedef void prog_void;
+//         typedef char prog_char;
+//         typedef unsigned char prog_uchar;
+//         typedef int8_t prog_int8_t;
+//         typedef uint8_t prog_uint8_t;
+//         typedef int16_t prog_int16_t;
+//         typedef uint16_t prog_uint16_t;
+//         typedef int32_t prog_int32_t;
+//         typedef uint32_t prog_uint32_t;
+
+//         #define strcpy_P(dest, src) strcpy((dest), (src))
+//         #define strcat_P(dest, src) strcat((dest), (src))
+//         #define strcmp_P(a, b) strcmp((a), (b))
+
+//         #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+//         #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+//         #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+//         #define pgm_read_float(addr) (*(const float *)(addr))
+
+//         #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+//         #define pgm_read_word_near(addr) pgm_read_word(addr)
+//         #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+//         #define pgm_read_float_near(addr) pgm_read_float(addr)
+//         #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+//         #define pgm_read_word_far(addr) pgm_read_word(addr)
+//         #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+//         #define pgm_read_float_far(addr) pgm_read_float(addr)
+//     #endif
+// #endif
+
+//Magnetometer Registers
+#define MPU9150_RA_MAG_ADDRESS		0x0C
+#define MPU9150_RA_MAG_XOUT_L		0x03
+#define MPU9150_RA_MAG_XOUT_H		0x04
+#define MPU9150_RA_MAG_YOUT_L		0x05
+#define MPU9150_RA_MAG_YOUT_H		0x06
+#define MPU9150_RA_MAG_ZOUT_L		0x07
+#define MPU9150_RA_MAG_ZOUT_H		0x08
+
+#define MPU9250_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU9250_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU9250_DEFAULT_ADDRESS     MPU9250_ADDRESS_AD0_LOW
+
+#define MPU9250_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9250_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9250_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9250_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU9250_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU9250_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU9250_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU9250_RA_XA_OFFS_L_TC     0x07
+#define MPU9250_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU9250_RA_YA_OFFS_L_TC     0x09
+#define MPU9250_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU9250_RA_ZA_OFFS_L_TC     0x0B
+#define MPU9250_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU9250_RA_XG_OFFS_USRL     0x14
+#define MPU9250_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU9250_RA_YG_OFFS_USRL     0x16
+#define MPU9250_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU9250_RA_ZG_OFFS_USRL     0x18
+#define MPU9250_RA_SMPLRT_DIV       0x19
+#define MPU9250_RA_CONFIG           0x1A
+#define MPU9250_RA_GYRO_CONFIG      0x1B
+#define MPU9250_RA_ACCEL_CONFIG     0x1C
+#define MPU9250_RA_FF_THR           0x1D
+#define MPU9250_RA_FF_DUR           0x1E
+#define MPU9250_RA_MOT_THR          0x1F
+#define MPU9250_RA_MOT_DUR          0x20
+#define MPU9250_RA_ZRMOT_THR        0x21
+#define MPU9250_RA_ZRMOT_DUR        0x22
+#define MPU9250_RA_FIFO_EN          0x23
+#define MPU9250_RA_I2C_MST_CTRL     0x24
+#define MPU9250_RA_I2C_SLV0_ADDR    0x25
+#define MPU9250_RA_I2C_SLV0_REG     0x26
+#define MPU9250_RA_I2C_SLV0_CTRL    0x27
+#define MPU9250_RA_I2C_SLV1_ADDR    0x28
+#define MPU9250_RA_I2C_SLV1_REG     0x29
+#define MPU9250_RA_I2C_SLV1_CTRL    0x2A
+#define MPU9250_RA_I2C_SLV2_ADDR    0x2B
+#define MPU9250_RA_I2C_SLV2_REG     0x2C
+#define MPU9250_RA_I2C_SLV2_CTRL    0x2D
+#define MPU9250_RA_I2C_SLV3_ADDR    0x2E
+#define MPU9250_RA_I2C_SLV3_REG     0x2F
+#define MPU9250_RA_I2C_SLV3_CTRL    0x30
+#define MPU9250_RA_I2C_SLV4_ADDR    0x31
+#define MPU9250_RA_I2C_SLV4_REG     0x32
+#define MPU9250_RA_I2C_SLV4_DO      0x33
+#define MPU9250_RA_I2C_SLV4_CTRL    0x34
+#define MPU9250_RA_I2C_SLV4_DI      0x35
+#define MPU9250_RA_I2C_MST_STATUS   0x36
+#define MPU9250_RA_INT_PIN_CFG      0x37
+#define MPU9250_RA_INT_ENABLE       0x38
+#define MPU9250_RA_DMP_INT_STATUS   0x39
+#define MPU9250_RA_INT_STATUS       0x3A
+#define MPU9250_RA_ACCEL_XOUT_H     0x3B
+#define MPU9250_RA_ACCEL_XOUT_L     0x3C
+#define MPU9250_RA_ACCEL_YOUT_H     0x3D
+#define MPU9250_RA_ACCEL_YOUT_L     0x3E
+#define MPU9250_RA_ACCEL_ZOUT_H     0x3F
+#define MPU9250_RA_ACCEL_ZOUT_L     0x40
+#define MPU9250_RA_TEMP_OUT_H       0x41
+#define MPU9250_RA_TEMP_OUT_L       0x42
+#define MPU9250_RA_GYRO_XOUT_H      0x43
+#define MPU9250_RA_GYRO_XOUT_L      0x44
+#define MPU9250_RA_GYRO_YOUT_H      0x45
+#define MPU9250_RA_GYRO_YOUT_L      0x46
+#define MPU9250_RA_GYRO_ZOUT_H      0x47
+#define MPU9250_RA_GYRO_ZOUT_L      0x48
+#define MPU9250_RA_EXT_SENS_DATA_00 0x49
+#define MPU9250_RA_EXT_SENS_DATA_01 0x4A
+#define MPU9250_RA_EXT_SENS_DATA_02 0x4B
+#define MPU9250_RA_EXT_SENS_DATA_03 0x4C
+#define MPU9250_RA_EXT_SENS_DATA_04 0x4D
+#define MPU9250_RA_EXT_SENS_DATA_05 0x4E
+#define MPU9250_RA_EXT_SENS_DATA_06 0x4F
+#define MPU9250_RA_EXT_SENS_DATA_07 0x50
+#define MPU9250_RA_EXT_SENS_DATA_08 0x51
+#define MPU9250_RA_EXT_SENS_DATA_09 0x52
+#define MPU9250_RA_EXT_SENS_DATA_10 0x53
+#define MPU9250_RA_EXT_SENS_DATA_11 0x54
+#define MPU9250_RA_EXT_SENS_DATA_12 0x55
+#define MPU9250_RA_EXT_SENS_DATA_13 0x56
+#define MPU9250_RA_EXT_SENS_DATA_14 0x57
+#define MPU9250_RA_EXT_SENS_DATA_15 0x58
+#define MPU9250_RA_EXT_SENS_DATA_16 0x59
+#define MPU9250_RA_EXT_SENS_DATA_17 0x5A
+#define MPU9250_RA_EXT_SENS_DATA_18 0x5B
+#define MPU9250_RA_EXT_SENS_DATA_19 0x5C
+#define MPU9250_RA_EXT_SENS_DATA_20 0x5D
+#define MPU9250_RA_EXT_SENS_DATA_21 0x5E
+#define MPU9250_RA_EXT_SENS_DATA_22 0x5F
+#define MPU9250_RA_EXT_SENS_DATA_23 0x60
+#define MPU9250_RA_MOT_DETECT_STATUS    0x61
+#define MPU9250_RA_I2C_SLV0_DO      0x63
+#define MPU9250_RA_I2C_SLV1_DO      0x64
+#define MPU9250_RA_I2C_SLV2_DO      0x65
+#define MPU9250_RA_I2C_SLV3_DO      0x66
+#define MPU9250_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU9250_RA_SIGNAL_PATH_RESET    0x68
+#define MPU9250_RA_MOT_DETECT_CTRL      0x69
+#define MPU9250_RA_USER_CTRL        0x6A
+#define MPU9250_RA_PWR_MGMT_1       0x6B
+#define MPU9250_RA_PWR_MGMT_2       0x6C
+#define MPU9250_RA_BANK_SEL         0x6D
+#define MPU9250_RA_MEM_START_ADDR   0x6E
+#define MPU9250_RA_MEM_R_W          0x6F
+#define MPU9250_RA_DMP_CFG_1        0x70
+#define MPU9250_RA_DMP_CFG_2        0x71
+#define MPU9250_RA_FIFO_COUNTH      0x72
+#define MPU9250_RA_FIFO_COUNTL      0x73
+#define MPU9250_RA_FIFO_R_W         0x74
+#define MPU9250_RA_WHO_AM_I         0x75
+
+#define MPU9250_TC_PWR_MODE_BIT     7
+#define MPU9250_TC_OFFSET_BIT       6
+#define MPU9250_TC_OFFSET_LENGTH    6
+#define MPU9250_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU9250_VDDIO_LEVEL_VLOGIC  0
+#define MPU9250_VDDIO_LEVEL_VDD     1
+
+#define MPU9250_CFG_EXT_SYNC_SET_BIT    5
+#define MPU9250_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU9250_CFG_DLPF_CFG_BIT    2
+#define MPU9250_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU9250_EXT_SYNC_DISABLED       0x0
+#define MPU9250_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU9250_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU9250_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU9250_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU9250_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU9250_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU9250_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU9250_DLPF_BW_256         0x00
+#define MPU9250_DLPF_BW_188         0x01
+#define MPU9250_DLPF_BW_98          0x02
+#define MPU9250_DLPF_BW_42          0x03
+#define MPU9250_DLPF_BW_20          0x04
+#define MPU9250_DLPF_BW_10          0x05
+#define MPU9250_DLPF_BW_5           0x06
+
+#define MPU9250_GCONFIG_FS_SEL_BIT      4
+#define MPU9250_GCONFIG_FS_SEL_LENGTH   2
+
+#define MPU9250_GYRO_FS_250         0x00
+#define MPU9250_GYRO_FS_500         0x01
+#define MPU9250_GYRO_FS_1000        0x02
+#define MPU9250_GYRO_FS_2000        0x03
+
+#define MPU9250_ACONFIG_XA_ST_BIT           7
+#define MPU9250_ACONFIG_YA_ST_BIT           6
+#define MPU9250_ACONFIG_ZA_ST_BIT           5
+#define MPU9250_ACONFIG_AFS_SEL_BIT         4
+#define MPU9250_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU9250_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU9250_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU9250_ACCEL_FS_2          0x00
+#define MPU9250_ACCEL_FS_4          0x01
+#define MPU9250_ACCEL_FS_8          0x02
+#define MPU9250_ACCEL_FS_16         0x03
+
+#define MPU9250_DHPF_RESET          0x00
+#define MPU9250_DHPF_5              0x01
+#define MPU9250_DHPF_2P5            0x02
+#define MPU9250_DHPF_1P25           0x03
+#define MPU9250_DHPF_0P63           0x04
+#define MPU9250_DHPF_HOLD           0x07
+
+#define MPU9250_TEMP_FIFO_EN_BIT    7
+#define MPU9250_XG_FIFO_EN_BIT      6
+#define MPU9250_YG_FIFO_EN_BIT      5
+#define MPU9250_ZG_FIFO_EN_BIT      4
+#define MPU9250_ACCEL_FIFO_EN_BIT   3
+#define MPU9250_SLV2_FIFO_EN_BIT    2
+#define MPU9250_SLV1_FIFO_EN_BIT    1
+#define MPU9250_SLV0_FIFO_EN_BIT    0
+
+#define MPU9250_MULT_MST_EN_BIT     7
+#define MPU9250_WAIT_FOR_ES_BIT     6
+#define MPU9250_SLV_3_FIFO_EN_BIT   5
+#define MPU9250_I2C_MST_P_NSR_BIT   4
+#define MPU9250_I2C_MST_CLK_BIT     3
+#define MPU9250_I2C_MST_CLK_LENGTH  4
+
+#define MPU9250_CLOCK_DIV_348       0x0
+#define MPU9250_CLOCK_DIV_333       0x1
+#define MPU9250_CLOCK_DIV_320       0x2
+#define MPU9250_CLOCK_DIV_308       0x3
+#define MPU9250_CLOCK_DIV_296       0x4
+#define MPU9250_CLOCK_DIV_286       0x5
+#define MPU9250_CLOCK_DIV_276       0x6
+#define MPU9250_CLOCK_DIV_267       0x7
+#define MPU9250_CLOCK_DIV_258       0x8
+#define MPU9250_CLOCK_DIV_500       0x9
+#define MPU9250_CLOCK_DIV_471       0xA
+#define MPU9250_CLOCK_DIV_444       0xB
+#define MPU9250_CLOCK_DIV_421       0xC
+#define MPU9250_CLOCK_DIV_400       0xD
+#define MPU9250_CLOCK_DIV_381       0xE
+#define MPU9250_CLOCK_DIV_364       0xF
+
+#define MPU9250_I2C_SLV_RW_BIT      7
+#define MPU9250_I2C_SLV_ADDR_BIT    6
+#define MPU9250_I2C_SLV_ADDR_LENGTH 7
+#define MPU9250_I2C_SLV_EN_BIT      7
+#define MPU9250_I2C_SLV_BYTE_SW_BIT 6
+#define MPU9250_I2C_SLV_REG_DIS_BIT 5
+#define MPU9250_I2C_SLV_GRP_BIT     4
+#define MPU9250_I2C_SLV_LEN_BIT     3
+#define MPU9250_I2C_SLV_LEN_LENGTH  4
+
+#define MPU9250_I2C_SLV4_RW_BIT         7
+#define MPU9250_I2C_SLV4_ADDR_BIT       6
+#define MPU9250_I2C_SLV4_ADDR_LENGTH    7
+#define MPU9250_I2C_SLV4_EN_BIT         7
+#define MPU9250_I2C_SLV4_INT_EN_BIT     6
+#define MPU9250_I2C_SLV4_REG_DIS_BIT    5
+#define MPU9250_I2C_SLV4_MST_DLY_BIT    4
+#define MPU9250_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU9250_MST_PASS_THROUGH_BIT    7
+#define MPU9250_MST_I2C_SLV4_DONE_BIT   6
+#define MPU9250_MST_I2C_LOST_ARB_BIT    5
+#define MPU9250_MST_I2C_SLV4_NACK_BIT   4
+#define MPU9250_MST_I2C_SLV3_NACK_BIT   3
+#define MPU9250_MST_I2C_SLV2_NACK_BIT   2
+#define MPU9250_MST_I2C_SLV1_NACK_BIT   1
+#define MPU9250_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU9250_INTCFG_INT_LEVEL_BIT        7
+#define MPU9250_INTCFG_INT_OPEN_BIT         6
+#define MPU9250_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU9250_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU9250_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU9250_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU9250_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU9250_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU9250_INTMODE_ACTIVEHIGH  0x00
+#define MPU9250_INTMODE_ACTIVELOW   0x01
+
+#define MPU9250_INTDRV_PUSHPULL     0x00
+#define MPU9250_INTDRV_OPENDRAIN    0x01
+
+#define MPU9250_INTLATCH_50USPULSE  0x00
+#define MPU9250_INTLATCH_WAITCLEAR  0x01
+
+#define MPU9250_INTCLEAR_STATUSREAD 0x00
+#define MPU9250_INTCLEAR_ANYREAD    0x01
+
+#define MPU9250_INTERRUPT_FF_BIT            7
+#define MPU9250_INTERRUPT_MOT_BIT           6
+#define MPU9250_INTERRUPT_ZMOT_BIT          5
+#define MPU9250_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU9250_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU9250_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU9250_INTERRUPT_DMP_INT_BIT       1
+#define MPU9250_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU9250_DMPINT_5_BIT            5
+#define MPU9250_DMPINT_4_BIT            4
+#define MPU9250_DMPINT_3_BIT            3
+#define MPU9250_DMPINT_2_BIT            2
+#define MPU9250_DMPINT_1_BIT            1
+#define MPU9250_DMPINT_0_BIT            0
+
+#define MPU9250_MOTION_MOT_XNEG_BIT     7
+#define MPU9250_MOTION_MOT_XPOS_BIT     6
+#define MPU9250_MOTION_MOT_YNEG_BIT     5
+#define MPU9250_MOTION_MOT_YPOS_BIT     4
+#define MPU9250_MOTION_MOT_ZNEG_BIT     3
+#define MPU9250_MOTION_MOT_ZPOS_BIT     2
+#define MPU9250_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU9250_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU9250_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU9250_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU9250_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU9250_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU9250_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU9250_PATHRESET_GYRO_RESET_BIT    2
+#define MPU9250_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU9250_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU9250_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU9250_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU9250_DETECT_FF_COUNT_BIT             3
+#define MPU9250_DETECT_FF_COUNT_LENGTH          2
+#define MPU9250_DETECT_MOT_COUNT_BIT            1
+#define MPU9250_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU9250_DETECT_DECREMENT_RESET  0x0
+#define MPU9250_DETECT_DECREMENT_1      0x1
+#define MPU9250_DETECT_DECREMENT_2      0x2
+#define MPU9250_DETECT_DECREMENT_4      0x3
+
+#define MPU9250_USERCTRL_DMP_EN_BIT             7
+#define MPU9250_USERCTRL_FIFO_EN_BIT            6
+#define MPU9250_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU9250_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU9250_USERCTRL_DMP_RESET_BIT          3
+#define MPU9250_USERCTRL_FIFO_RESET_BIT         2
+#define MPU9250_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU9250_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU9250_PWR1_DEVICE_RESET_BIT   7
+#define MPU9250_PWR1_SLEEP_BIT          6
+#define MPU9250_PWR1_CYCLE_BIT          5
+#define MPU9250_PWR1_TEMP_DIS_BIT       3
+#define MPU9250_PWR1_CLKSEL_BIT         2
+#define MPU9250_PWR1_CLKSEL_LENGTH      3
+
+#define MPU9250_CLOCK_INTERNAL          0x00
+#define MPU9250_CLOCK_PLL_XGYRO         0x01
+#define MPU9250_CLOCK_PLL_YGYRO         0x02
+#define MPU9250_CLOCK_PLL_ZGYRO         0x03
+#define MPU9250_CLOCK_PLL_EXT32K        0x04
+#define MPU9250_CLOCK_PLL_EXT19M        0x05
+#define MPU9250_CLOCK_KEEP_RESET        0x07
+
+#define MPU9250_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU9250_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU9250_PWR2_STBY_XA_BIT            5
+#define MPU9250_PWR2_STBY_YA_BIT            4
+#define MPU9250_PWR2_STBY_ZA_BIT            3
+#define MPU9250_PWR2_STBY_XG_BIT            2
+#define MPU9250_PWR2_STBY_YG_BIT            1
+#define MPU9250_PWR2_STBY_ZG_BIT            0
+
+#define MPU9250_WAKE_FREQ_1P25      0x0
+#define MPU9250_WAKE_FREQ_2P5       0x1
+#define MPU9250_WAKE_FREQ_5         0x2
+#define MPU9250_WAKE_FREQ_10        0x3
+
+#define MPU9250_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU9250_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU9250_BANKSEL_MEM_SEL_BIT         4
+#define MPU9250_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU9250_WHO_AM_I_BIT        6
+//TODO: VERIFY THIS!
+// #define MPU9250_WHO_AM_I_LENGTH     8
+#define MPU9250_WHO_AM_I_LENGTH     6
+
+
+#define MPU9250_DMP_MEMORY_BANKS        8
+#define MPU9250_DMP_MEMORY_BANK_SIZE    256
+#define MPU9250_DMP_MEMORY_CHUNK_SIZE   16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU9250 {
+    public:
+        MPU9250();
+        MPU9250(uint8_t address);
+
+        void initialize();
+        bool testConnection();
+
+        // AUX_VDDIO register
+        uint8_t getAuxVDDIOLevel();
+        void setAuxVDDIOLevel(uint8_t level);
+
+        // SMPLRT_DIV register
+        uint8_t getRate();
+        void setRate(uint8_t rate);
+
+        // CONFIG register
+        uint8_t getExternalFrameSync();
+        void setExternalFrameSync(uint8_t sync);
+        uint8_t getDLPFMode();
+        void setDLPFMode(uint8_t bandwidth);
+
+        // GYRO_CONFIG register
+        uint8_t getFullScaleGyroRange();
+        void setFullScaleGyroRange(uint8_t range);
+
+        // ACCEL_CONFIG register
+        bool getAccelXSelfTest();
+        void setAccelXSelfTest(bool enabled);
+        bool getAccelYSelfTest();
+        void setAccelYSelfTest(bool enabled);
+        bool getAccelZSelfTest();
+        void setAccelZSelfTest(bool enabled);
+        uint8_t getFullScaleAccelRange();
+        void setFullScaleAccelRange(uint8_t range);
+        uint8_t getDHPFMode();
+        void setDHPFMode(uint8_t mode);
+
+        // FF_THR register
+        uint8_t getFreefallDetectionThreshold();
+        void setFreefallDetectionThreshold(uint8_t threshold);
+
+        // FF_DUR register
+        uint8_t getFreefallDetectionDuration();
+        void setFreefallDetectionDuration(uint8_t duration);
+
+        // MOT_THR register
+        uint8_t getMotionDetectionThreshold();
+        void setMotionDetectionThreshold(uint8_t threshold);
+
+        // MOT_DUR register
+        uint8_t getMotionDetectionDuration();
+        void setMotionDetectionDuration(uint8_t duration);
+
+        // ZRMOT_THR register
+        uint8_t getZeroMotionDetectionThreshold();
+        void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+        // ZRMOT_DUR register
+        uint8_t getZeroMotionDetectionDuration();
+        void setZeroMotionDetectionDuration(uint8_t duration);
+
+        // FIFO_EN register
+        bool getTempFIFOEnabled();
+        void setTempFIFOEnabled(bool enabled);
+        bool getXGyroFIFOEnabled();
+        void setXGyroFIFOEnabled(bool enabled);
+        bool getYGyroFIFOEnabled();
+        void setYGyroFIFOEnabled(bool enabled);
+        bool getZGyroFIFOEnabled();
+        void setZGyroFIFOEnabled(bool enabled);
+        bool getAccelFIFOEnabled();
+        void setAccelFIFOEnabled(bool enabled);
+        bool getSlave2FIFOEnabled();
+        void setSlave2FIFOEnabled(bool enabled);
+        bool getSlave1FIFOEnabled();
+        void setSlave1FIFOEnabled(bool enabled);
+        bool getSlave0FIFOEnabled();
+        void setSlave0FIFOEnabled(bool enabled);
+
+        // I2C_MST_CTRL register
+        bool getMultiMasterEnabled();
+        void setMultiMasterEnabled(bool enabled);
+        bool getWaitForExternalSensorEnabled();
+        void setWaitForExternalSensorEnabled(bool enabled);
+        bool getSlave3FIFOEnabled();
+        void setSlave3FIFOEnabled(bool enabled);
+        bool getSlaveReadWriteTransitionEnabled();
+        void setSlaveReadWriteTransitionEnabled(bool enabled);
+        uint8_t getMasterClockSpeed();
+        void setMasterClockSpeed(uint8_t speed);
+
+        // I2C_SLV* registers (Slave 0-3)
+        uint8_t getSlaveAddress(uint8_t num);
+        void setSlaveAddress(uint8_t num, uint8_t address);
+        uint8_t getSlaveRegister(uint8_t num);
+        void setSlaveRegister(uint8_t num, uint8_t reg);
+        bool getSlaveEnabled(uint8_t num);
+        void setSlaveEnabled(uint8_t num, bool enabled);
+        bool getSlaveWordByteSwap(uint8_t num);
+        void setSlaveWordByteSwap(uint8_t num, bool enabled);
+        bool getSlaveWriteMode(uint8_t num);
+        void setSlaveWriteMode(uint8_t num, bool mode);
+        bool getSlaveWordGroupOffset(uint8_t num);
+        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+        uint8_t getSlaveDataLength(uint8_t num);
+        void setSlaveDataLength(uint8_t num, uint8_t length);
+
+        // I2C_SLV* registers (Slave 4)
+        uint8_t getSlave4Address();
+        void setSlave4Address(uint8_t address);
+        uint8_t getSlave4Register();
+        void setSlave4Register(uint8_t reg);
+        void setSlave4OutputByte(uint8_t data);
+        bool getSlave4Enabled();
+        void setSlave4Enabled(bool enabled);
+        bool getSlave4InterruptEnabled();
+        void setSlave4InterruptEnabled(bool enabled);
+        bool getSlave4WriteMode();
+        void setSlave4WriteMode(bool mode);
+        uint8_t getSlave4MasterDelay();
+        void setSlave4MasterDelay(uint8_t delay);
+        uint8_t getSlate4InputByte();
+
+        // I2C_MST_STATUS register
+        bool getPassthroughStatus();
+        bool getSlave4IsDone();
+        bool getLostArbitration();
+        bool getSlave4Nack();
+        bool getSlave3Nack();
+        bool getSlave2Nack();
+        bool getSlave1Nack();
+        bool getSlave0Nack();
+
+        // INT_PIN_CFG register
+        bool getInterruptMode();
+        void setInterruptMode(bool mode);
+        bool getInterruptDrive();
+        void setInterruptDrive(bool drive);
+        bool getInterruptLatch();
+        void setInterruptLatch(bool latch);
+        bool getInterruptLatchClear();
+        void setInterruptLatchClear(bool clear);
+        bool getFSyncInterruptLevel();
+        void setFSyncInterruptLevel(bool level);
+        bool getFSyncInterruptEnabled();
+        void setFSyncInterruptEnabled(bool enabled);
+        bool getI2CBypassEnabled();
+        void setI2CBypassEnabled(bool enabled);
+        bool getClockOutputEnabled();
+        void setClockOutputEnabled(bool enabled);
+
+        // INT_ENABLE register
+        uint8_t getIntEnabled();
+        void setIntEnabled(uint8_t enabled);
+        bool getIntFreefallEnabled();
+        void setIntFreefallEnabled(bool enabled);
+        bool getIntMotionEnabled();
+        void setIntMotionEnabled(bool enabled);
+        bool getIntZeroMotionEnabled();
+        void setIntZeroMotionEnabled(bool enabled);
+        bool getIntFIFOBufferOverflowEnabled();
+        void setIntFIFOBufferOverflowEnabled(bool enabled);
+        bool getIntI2CMasterEnabled();
+        void setIntI2CMasterEnabled(bool enabled);
+        bool getIntDataReadyEnabled();
+        void setIntDataReadyEnabled(bool enabled);
+
+        // INT_STATUS register
+        uint8_t getIntStatus();
+        bool getIntFreefallStatus();
+        bool getIntMotionStatus();
+        bool getIntZeroMotionStatus();
+        bool getIntFIFOBufferOverflowStatus();
+        bool getIntI2CMasterStatus();
+        bool getIntDataReadyStatus();
+
+        // ACCEL_*OUT_* registers
+        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getAccelerationX();
+        int16_t getAccelerationY();
+        int16_t getAccelerationZ();
+
+        // TEMP_OUT_* registers
+        int16_t getTemperature();
+
+        void getHeading(int16_t* mx, int16_t* my, int16_t* mz);
+
+        // GYRO_*OUT_* registers
+        void getRotation(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getRotationX();
+        int16_t getRotationY();
+        int16_t getRotationZ();
+
+        // EXT_SENS_DATA_* registers
+        uint8_t getExternalSensorByte(int position);
+        uint16_t getExternalSensorWord(int position);
+        uint32_t getExternalSensorDWord(int position);
+
+        // MOT_DETECT_STATUS register
+        bool getXNegMotionDetected();
+        bool getXPosMotionDetected();
+        bool getYNegMotionDetected();
+        bool getYPosMotionDetected();
+        bool getZNegMotionDetected();
+        bool getZPosMotionDetected();
+        bool getZeroMotionDetected();
+
+        // I2C_SLV*_DO register
+        void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+        // I2C_MST_DELAY_CTRL register
+        bool getExternalShadowDelayEnabled();
+        void setExternalShadowDelayEnabled(bool enabled);
+        bool getSlaveDelayEnabled(uint8_t num);
+        void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+        // SIGNAL_PATH_RESET register
+        void resetGyroscopePath();
+        void resetAccelerometerPath();
+        void resetTemperaturePath();
+
+        // MOT_DETECT_CTRL register
+        uint8_t getAccelerometerPowerOnDelay();
+        void setAccelerometerPowerOnDelay(uint8_t delay);
+        uint8_t getFreefallDetectionCounterDecrement();
+        void setFreefallDetectionCounterDecrement(uint8_t decrement);
+        uint8_t getMotionDetectionCounterDecrement();
+        void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+        // USER_CTRL register
+        bool getFIFOEnabled();
+        void setFIFOEnabled(bool enabled);
+        bool getI2CMasterModeEnabled();
+        void setI2CMasterModeEnabled(bool enabled);
+        void switchSPIEnabled(bool enabled);
+        void resetFIFO();
+        void resetI2CMaster();
+        void resetSensors();
+
+        // PWR_MGMT_1 register
+        void reset();
+        bool getSleepEnabled();
+        void setSleepEnabled(bool enabled);
+        bool getWakeCycleEnabled();
+        void setWakeCycleEnabled(bool enabled);
+        bool getTempSensorEnabled();
+        void setTempSensorEnabled(bool enabled);
+        uint8_t getClockSource();
+        void setClockSource(uint8_t source);
+
+        // PWR_MGMT_2 register
+        uint8_t getWakeFrequency();
+        void setWakeFrequency(uint8_t frequency);
+        bool getStandbyXAccelEnabled();
+        void setStandbyXAccelEnabled(bool enabled);
+        bool getStandbyYAccelEnabled();
+        void setStandbyYAccelEnabled(bool enabled);
+        bool getStandbyZAccelEnabled();
+        void setStandbyZAccelEnabled(bool enabled);
+        bool getStandbyXGyroEnabled();
+        void setStandbyXGyroEnabled(bool enabled);
+        bool getStandbyYGyroEnabled();
+        void setStandbyYGyroEnabled(bool enabled);
+        bool getStandbyZGyroEnabled();
+        void setStandbyZGyroEnabled(bool enabled);
+
+        // FIFO_COUNT_* registers
+        uint16_t getFIFOCount();
+
+        // FIFO_R_W register
+        uint8_t getFIFOByte();
+        void setFIFOByte(uint8_t data);
+        void getFIFOBytes(uint8_t *data, uint8_t length);
+
+        // WHO_AM_I register
+        uint8_t getDeviceID();
+        void setDeviceID(uint8_t id);
+        
+        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+        
+        // XG_OFFS_TC register
+        uint8_t getOTPBankValid();
+        void setOTPBankValid(bool enabled);
+        int8_t getXGyroOffset();
+        void setXGyroOffset(int8_t offset);
+
+        // YG_OFFS_TC register
+        int8_t getYGyroOffset();
+        void setYGyroOffset(int8_t offset);
+
+        // ZG_OFFS_TC register
+        int8_t getZGyroOffset();
+        void setZGyroOffset(int8_t offset);
+
+        // X_FINE_GAIN register
+        int8_t getXFineGain();
+        void setXFineGain(int8_t gain);
+
+        // Y_FINE_GAIN register
+        int8_t getYFineGain();
+        void setYFineGain(int8_t gain);
+
+        // Z_FINE_GAIN register
+        int8_t getZFineGain();
+        void setZFineGain(int8_t gain);
+
+        // XA_OFFS_* registers
+        int16_t getXAccelOffset();
+        void setXAccelOffset(int16_t offset);
+
+        // YA_OFFS_* register
+        int16_t getYAccelOffset();
+        void setYAccelOffset(int16_t offset);
+
+        // ZA_OFFS_* register
+        int16_t getZAccelOffset();
+        void setZAccelOffset(int16_t offset);
+
+        // XG_OFFS_USR* registers
+        int16_t getXGyroOffsetUser();
+        void setXGyroOffsetUser(int16_t offset);
+
+        // YG_OFFS_USR* register
+        int16_t getYGyroOffsetUser();
+        void setYGyroOffsetUser(int16_t offset);
+
+        // ZG_OFFS_USR* register
+        int16_t getZGyroOffsetUser();
+        void setZGyroOffsetUser(int16_t offset);
+        
+        // INT_ENABLE register (DMP functions)
+        bool getIntPLLReadyEnabled();
+        void setIntPLLReadyEnabled(bool enabled);
+        bool getIntDMPEnabled();
+        void setIntDMPEnabled(bool enabled);
+        
+        // DMP_INT_STATUS
+        bool getDMPInt5Status();
+        bool getDMPInt4Status();
+        bool getDMPInt3Status();
+        bool getDMPInt2Status();
+        bool getDMPInt1Status();
+        bool getDMPInt0Status();
+
+        // INT_STATUS register (DMP functions)
+        bool getIntPLLReadyStatus();
+        bool getIntDMPStatus();
+        
+        // USER_CTRL register (DMP functions)
+        bool getDMPEnabled();
+        void setDMPEnabled(bool enabled);
+        void resetDMP();
+        
+        // BANK_SEL register
+        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+        
+        // MEM_START_ADDR register
+        void setMemoryStartAddress(uint8_t address);
+        
+        // MEM_R_W register
+        uint8_t readMemoryByte();
+        void writeMemoryByte(uint8_t data);
+        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+        // DMP_CFG_1 register
+        uint8_t getDMPConfig1();
+        void setDMPConfig1(uint8_t config);
+
+        // DMP_CFG_2 register
+        uint8_t getDMPConfig2();
+        void setDMPConfig2(uint8_t config);
+
+        // special methods for MotionApps 2.0 implementation
+        #ifdef MPU9250_INCLUDE_DMP_MOTIONAPPS20
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+        // special methods for MotionApps 4.1 implementation
+        #ifdef MPU9250_INCLUDE_DMP_MOTIONAPPS41
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[14];
+};
+
+#endif /* _MPU9250_H_ */
\ No newline at end of file
diff --git a/firmware/lib/imu/default_imu.h b/firmware/lib/imu/default_imu.h
new file mode 100644
index 0000000..f3aba41
--- /dev/null
+++ b/firmware/lib/imu/default_imu.h
@@ -0,0 +1,400 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef DEFAULT_IMU
+#define DEFAULT_IMU
+
+//include IMU base interface
+#include "imu_interface.h"
+
+//include sensor API headers
+#include "I2Cdev.h"
+#include "ADXL345.h"
+#include "ITG3200.h"
+#include "HMC5883L.h"
+#include "MPU6050.h"
+#include "MPU9150.h"
+#include "MPU9250.h"
+#include "MPU9250_WE.h"
+
+class GY85IMU: public IMUInterface 
+{
+    private:
+        //constants specific to the sensor
+        const float accel_scale_ = 1 / 256.0;
+        const float gyro_scale_ = 1 / 14.375;
+
+        // driver objects to be used
+        ADXL345 accelerometer_;
+        ITG3200 gyroscope_;
+
+        // returned vector for sensor reading
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        GY85IMU()
+        {
+            // accel_cov_ = 0.001; //you can overwrite the convariance values here
+            // gyro_cov_ = 0.001; //you can overwrite the convariance values here
+        }
+
+        bool startSensor() override
+        {
+            // here you can override startSensor() function and use the sensor's driver API
+            // to initialize and test the sensor's connection during boot time
+            Wire.begin();
+            bool ret;
+            accelerometer_.initialize();
+            ret = accelerometer_.testConnection();
+            if(!ret)
+                return false;
+
+            gyroscope_.initialize();
+            ret = gyroscope_.testConnection();
+            if(!ret)
+                return false;
+
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            // here you can override readAccelerometer function and use the sensor's driver API
+            // to grab the data from accelerometer and return as a Vector3 object
+            int16_t ax, ay, az;
+            
+            accelerometer_.getAcceleration(&ax, &ay, &az);
+
+            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
+            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
+            accel_.z = az * (double) accel_scale_ * g_to_accel_;
+
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            // here you can override readAccelerometer function and use the sensor's driver API
+            // to grab the data from gyroscope and return as a Vector3 object
+            int16_t gx, gy, gz;
+
+            gyroscope_.getRotation(&gx, &gy, &gz);
+
+            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
+
+            return gyro_;
+        }
+};
+
+
+class MPU6050IMU: public IMUInterface 
+{
+    private:
+        const float accel_scale_ = 1 / 16384.0;
+        const float gyro_scale_ = 1 / 131.0;
+
+        MPU6050 accelerometer_;
+        MPU6050 gyroscope_;
+
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        MPU6050IMU()
+        {
+        }
+
+        bool startSensor() override
+        {
+            Wire.begin();
+            bool ret;
+            accelerometer_.initialize();
+            ret = accelerometer_.testConnection();
+            if(!ret)
+                return false;
+
+            gyroscope_.initialize();
+            ret = gyroscope_.testConnection();
+            if(!ret)
+                return false;
+
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            int16_t ax, ay, az;
+            
+            accelerometer_.getAcceleration(&ax, &ay, &az);
+
+            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
+            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
+            accel_.z = az * (double) accel_scale_ * g_to_accel_;
+
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            int16_t gx, gy, gz;
+
+            gyroscope_.getRotation(&gx, &gy, &gz);
+
+            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
+
+            return gyro_;
+        }
+};
+
+class MPU9150IMU: public IMUInterface 
+{
+    private:
+        const float accel_scale_ = 1 / 16384.0;
+        const float gyro_scale_ = 1 / 131.0;
+
+        MPU9150 accelerometer_;
+        MPU9150 gyroscope_;
+
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        MPU9150IMU()
+        {
+        }
+
+        bool startSensor() override
+        {
+            Wire.begin();
+            bool ret;
+            accelerometer_.initialize();
+            ret = accelerometer_.testConnection();
+            if(!ret)
+                return false;
+
+            gyroscope_.initialize();
+            ret = gyroscope_.testConnection();
+            if(!ret)
+                return false;
+
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            int16_t ax, ay, az;
+            
+            accelerometer_.getAcceleration(&ax, &ay, &az);
+
+            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
+            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
+            accel_.z = az * (double) accel_scale_ * g_to_accel_;
+
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            int16_t gx, gy, gz;
+
+            gyroscope_.getRotation(&gx, &gy, &gz);
+
+            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
+
+            return gyro_;
+        }
+};
+
+class MPU9250IMU: public IMUInterface 
+{
+    private:
+        const float accel_scale_ = 1 / 16384.0;
+        const float gyro_scale_ = 1 / 131.0;
+
+        MPU9250 accelerometer_;
+        MPU9250 gyroscope_;
+
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        MPU9250IMU()
+        {
+        }
+
+        bool startSensor() override
+        {
+            Wire.begin();
+            bool ret;
+            accelerometer_.initialize();
+            ret = accelerometer_.testConnection();
+            if(!ret)
+                return false;
+
+            gyroscope_.initialize();
+            ret = gyroscope_.testConnection();
+            if(!ret)
+                return false;
+
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            int16_t ax, ay, az;
+            
+            accelerometer_.getAcceleration(&ax, &ay, &az);
+
+            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
+            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
+            accel_.z = az * (double) accel_scale_ * g_to_accel_;
+
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            int16_t gx, gy, gz;
+
+            gyroscope_.getRotation(&gx, &gy, &gz);
+
+            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
+
+            return gyro_;
+        }
+};
+
+class MPU9250IMU_WE: public IMUInterface 
+{
+    private:
+        const float accel_scale_ = 1 / 16384.0;
+        const float gyro_scale_ = 1 / 131.0;
+
+        MPU9250_WE accelerometer_;
+        MPU9250_WE gyroscope_;
+
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        MPU9250IMU_WE()
+        {
+        }
+
+        bool startSensor() override
+        {
+            Wire.begin();
+            bool ret;
+            accelerometer_.init();
+            ret = accelerometer_.init();
+            if(!ret)
+                return false;
+
+            gyroscope_.init();
+            ret = gyroscope_.init();
+            if(!ret)
+                return false;
+
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            //int16_t ax, ay, az;
+                
+            xyzFloat xyz_Gval = accelerometer_.getGValues();
+            // ax = static_cast(xyz_Gval.x); // Convert x to an integer
+            // ay = static_cast(xyz_Gval.y); // Convert y to an integer
+            // az = static_cast(xyz_Gval.z); // Convert z to an integer
+
+            float ax = xyz_Gval.x; // Convert x to an integer
+            float ay = xyz_Gval.y; // Convert y to an integer
+            float az = xyz_Gval.z; // Convert z to an integer
+
+            accel_.x = ax * (double) accel_scale_ * g_to_accel_;
+            accel_.y = ay * (double) accel_scale_ * g_to_accel_;
+            accel_.z = az * (double) accel_scale_ * g_to_accel_;
+
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            //int16_t gx, gy, gz;
+
+            xyzFloat xyz_gyr = gyroscope_.getGyrValues();
+            // gx = static_cast(xyz_gyr.x); // Convert x to an integer
+            // gy = static_cast(xyz_gyr.y); // Convert y to an integer
+            // gz = static_cast(xyz_gyr.z); // Convert z to an integer
+
+            float gx = xyz_gyr.x; // Convert x to an integer
+            float gy = xyz_gyr.y; // Convert y to an integer
+            float gz = xyz_gyr.z; // Convert z to an integer
+
+            gyro_.x = gx * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.y = gy * (double) gyro_scale_ * DEG_TO_RAD;
+            gyro_.z = gz * (double) gyro_scale_ * DEG_TO_RAD;
+
+            return gyro_;
+        }
+};
+
+class FakeIMU: public IMUInterface 
+{
+    private:
+        geometry_msgs__msg__Vector3 accel_;
+        geometry_msgs__msg__Vector3 gyro_;
+
+    public:
+        FakeIMU()
+        {
+        }
+
+        bool startSensor() override
+        {
+            return true;
+        }
+
+        geometry_msgs__msg__Vector3 readAccelerometer() override
+        {
+            return accel_;
+        }
+
+        geometry_msgs__msg__Vector3 readGyroscope() override
+        {
+            return gyro_;
+        }
+};
+
+#endif
+//ADXL345 https://www.sparkfun.com/datasheets/Sensors/Accelerometer/ADXL345.pdf
+//HMC8553L https://cdn-shop.adafruit.com/datasheets/HMC5883L_3-Axis_Digital_Compass_IC.pdf
+//ITG320 https://www.sparkfun.com/datasheets/Sensors/Gyro/PS-ITG-3200-00-01.4.pdf
+
+
+//MPU9150 https://www.invensense.com/wp-content/uploads/2015/02/PS-MPU-9250A-01-v1.1.pdf
+//MPU9250 https://www.invensense.com/wp-content/uploads/2015/02/MPU-9150-Datasheet.pdf
+//MPU6050 https://store.invensense.com/datasheets/invensense/MPU-6050_DataSheet_V3%204.pdf
+
+//http://www.sureshjoshi.com/embedded/invensense-imus-what-to-know/
+//https://stackoverflow.com/questions/19161872/meaning-of-lsb-unit-and-unit-lsb
\ No newline at end of file
diff --git a/firmware/lib/imu/fake_mag.h b/firmware/lib/imu/fake_mag.h
new file mode 100644
index 0000000..8af6191
--- /dev/null
+++ b/firmware/lib/imu/fake_mag.h
@@ -0,0 +1,38 @@
+#ifndef _FAKE_MAG_H_
+#define _FAKE_MAG_H_
+
+
+//This is a pseudo Magnetometer Class as a placeholder for IMUs that do not have a Magnetometer
+
+class FakeMag
+{
+    public:
+        FakeMag();
+        bool initialize();
+        bool testConnection();
+        void getHeading(int16_t* mx, int16_t* my, int16_t* mz);
+};
+
+FakeMag::FakeMag()
+{
+
+}
+
+bool  FakeMag::initialize()
+{
+    return true;
+}
+
+bool  FakeMag::testConnection()
+{
+    return true;
+}
+
+void FakeMag::getHeading(int16_t* mx, int16_t* my, int16_t* mz)
+{
+    *mx = 0;
+    *my = 0;
+    *mz = 0;
+}
+
+#endif
\ No newline at end of file
diff --git a/firmware/lib/imu/imu.h b/firmware/lib/imu/imu.h
new file mode 100644
index 0000000..d2f47a0
--- /dev/null
+++ b/firmware/lib/imu/imu.h
@@ -0,0 +1,48 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef IMU_CONFIG_H
+#define IMU_CONFIG_H
+
+// include the header of your new driver here similar to default_imu.h
+#include "default_imu.h"
+
+// now you can create a config constant that you can use in lino_base_config.h
+#ifdef USE_GY85_IMU
+    // pass your built in class to IMU macro
+    #define IMU GY85IMU
+#endif
+
+#ifdef USE_MPU6050_IMU
+    #define IMU MPU6050IMU
+#endif
+
+#ifdef USE_MPU9150_IMU
+    #define IMU MPU9150IMU
+#endif
+
+#ifdef USE_MPU9250_IMU
+    #define IMU MPU9250IMU
+#endif
+
+#ifdef USE_MPU9250_WE_IMU
+    #define IMU MPU9250IMU_WE
+#endif
+
+#ifdef USE_FAKE_IMU
+    #define IMU FakeIMU
+#endif
+
+#endif
+
diff --git a/firmware/lib/imu/imu_interface.h b/firmware/lib/imu/imu_interface.h
new file mode 100644
index 0000000..571607a
--- /dev/null
+++ b/firmware/lib/imu/imu_interface.h
@@ -0,0 +1,101 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef IMU_INTERFACE
+#define IMU_INTERFACE
+
+#include 
+
+class IMUInterface
+{
+    protected:
+        sensor_msgs__msg__Imu imu_msg_;
+        const float g_to_accel_ = 9.81;
+        const float mgauss_to_utesla_ = 0.1;
+        const float utesla_to_tesla_ = 0.000001;
+
+        float accel_cov_ = 0.00001;
+        float gyro_cov_ = 0.00001;
+        const int sample_size_ = 40;
+
+        geometry_msgs__msg__Vector3 gyro_cal_;
+
+        void calibrateGyro()
+        {
+            geometry_msgs__msg__Vector3 gyro;
+
+            for(int i=0; i -0.01 && imu_msg_.angular_velocity.x < 0.01 )
+                imu_msg_.angular_velocity.x = 0; 
+         
+            if(imu_msg_.angular_velocity.y > -0.01 && imu_msg_.angular_velocity.y < 0.01 )
+                imu_msg_.angular_velocity.y = 0;
+
+            if(imu_msg_.angular_velocity.z > -0.01 && imu_msg_.angular_velocity.z < 0.01 )
+                imu_msg_.angular_velocity.z = 0;
+       
+            imu_msg_.angular_velocity_covariance[0] = gyro_cov_;
+            imu_msg_.angular_velocity_covariance[4] = gyro_cov_;
+            imu_msg_.angular_velocity_covariance[8] = gyro_cov_;
+            
+            imu_msg_.linear_acceleration = readAccelerometer();
+            imu_msg_.linear_acceleration_covariance[0] = accel_cov_;
+            imu_msg_.linear_acceleration_covariance[4] = accel_cov_;
+            imu_msg_.linear_acceleration_covariance[8] = accel_cov_;
+
+            return imu_msg_;
+        }
+};
+
+#endif
diff --git a/firmware/lib/kinematics/kinematics.cpp b/firmware/lib/kinematics/kinematics.cpp
new file mode 100644
index 0000000..c1e1818
--- /dev/null
+++ b/firmware/lib/kinematics/kinematics.cpp
@@ -0,0 +1,149 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "Arduino.h"
+#include "kinematics.h"
+
+Kinematics::Kinematics(base robot_base, int motor_max_rpm, float max_rpm_ratio,
+                       float motor_operating_voltage, float motor_power_max_voltage,
+                       float wheel_diameter, float wheels_y_distance):
+    base_platform_(robot_base),
+    wheels_y_distance_(wheels_y_distance),
+    wheel_circumference_(PI * wheel_diameter),
+    total_wheels_(getTotalWheels(robot_base))
+{    
+    motor_power_max_voltage = constrain(motor_power_max_voltage, 0, motor_operating_voltage);
+    max_rpm_ =  ((motor_power_max_voltage / motor_operating_voltage) * motor_max_rpm) * max_rpm_ratio;
+}
+
+Kinematics::rpm Kinematics::calculateRPM(float linear_x, float linear_y, float angular_z)
+{
+
+    float tangential_vel = angular_z * (wheels_y_distance_ / 2.0);
+
+    //convert m/s to m/min
+    float linear_vel_x_mins = linear_x * 60.0;
+    float linear_vel_y_mins = linear_y * 60.0;
+    //convert rad/s to rad/min
+    float tangential_vel_mins = tangential_vel * 60.0;
+
+    float x_rpm = linear_vel_x_mins / wheel_circumference_;
+    float y_rpm = linear_vel_y_mins / wheel_circumference_;
+    float tan_rpm = tangential_vel_mins / wheel_circumference_;
+
+    float a_x_rpm = fabs(x_rpm);
+    float a_y_rpm = fabs(y_rpm);
+    float a_tan_rpm = fabs(tan_rpm);
+
+    float xy_sum = a_x_rpm + a_y_rpm;
+    float xtan_sum = a_x_rpm + a_tan_rpm;
+
+    //calculate the scale value how much each target velocity
+    //must be scaled down in such cases where the total required RPM
+    //is more than the motor's max RPM
+    //this is to ensure that the required motion is achieved just with slower speed
+    if(xy_sum >= max_rpm_ && angular_z == 0)
+    {
+        float vel_scaler = max_rpm_ / xy_sum;
+
+        x_rpm *= vel_scaler;
+        y_rpm *= vel_scaler;
+    }
+    
+    else if(xtan_sum >= max_rpm_ && linear_y == 0)
+    {
+        float vel_scaler = max_rpm_ / xtan_sum;
+
+        x_rpm *= vel_scaler;
+        tan_rpm *= vel_scaler;
+    }
+
+    Kinematics::rpm rpm;
+
+    //calculate for the target motor RPM and direction
+    //front-left motor
+    rpm.motor1 = x_rpm - y_rpm - tan_rpm;
+    rpm.motor1 = constrain(rpm.motor1, -max_rpm_, max_rpm_);
+
+    //front-right motor
+    rpm.motor2 = x_rpm + y_rpm + tan_rpm;
+    rpm.motor2 = constrain(rpm.motor2, -max_rpm_, max_rpm_);
+
+    //rear-left motor
+    rpm.motor3 = x_rpm + y_rpm - tan_rpm;
+    rpm.motor3 = constrain(rpm.motor3, -max_rpm_, max_rpm_);
+
+    //rear-right motor
+    rpm.motor4 = x_rpm - y_rpm + tan_rpm;
+    rpm.motor4 = constrain(rpm.motor4, -max_rpm_, max_rpm_);
+
+    return rpm;
+}
+
+Kinematics::rpm Kinematics::getRPM(float linear_x, float linear_y, float angular_z)
+{
+    if(base_platform_ == DIFFERENTIAL_DRIVE || base_platform_ == SKID_STEER)
+    {
+        linear_y = 0;
+    }
+
+    return calculateRPM(linear_x, linear_y, angular_z);;
+}
+
+Kinematics::velocities Kinematics::getVelocities(float rpm1, float rpm2, float rpm3, float rpm4)
+{
+    Kinematics::velocities vel;
+    float average_rps_x;
+    float average_rps_y;
+    float average_rps_a;
+
+    if(base_platform_ == DIFFERENTIAL_DRIVE)
+    {
+        rpm3 = 0.0;
+        rpm4 = 0.0;
+    }
+ 
+    //convert average revolutions per minute to revolutions per second
+    average_rps_x = ((float)(rpm1 + rpm2 + rpm3 + rpm4) / total_wheels_) / 60.0; // RPM
+    vel.linear_x = average_rps_x * wheel_circumference_; // m/s
+
+    //convert average revolutions per minute in y axis to revolutions per second
+    average_rps_y = ((float)(-rpm1 + rpm2 + rpm3 - rpm4) / total_wheels_) / 60.0; // RPM
+    if(base_platform_ == MECANUM)
+        vel.linear_y = average_rps_y * wheel_circumference_; // m/s
+    else
+        vel.linear_y = 0;
+
+    //convert average revolutions per minute to revolutions per second
+    average_rps_a = ((float)(-rpm1 + rpm2 - rpm3 + rpm4) / total_wheels_) / 60.0;
+    vel.angular_z =  (average_rps_a * wheel_circumference_) / (wheels_y_distance_ / 2.0); //  rad/s
+
+    return vel;
+}
+
+int Kinematics::getTotalWheels(base robot_base)
+{
+    switch(robot_base)
+    {
+        case DIFFERENTIAL_DRIVE:    return 2;
+        case SKID_STEER:            return 4;
+        case MECANUM:               return 4;
+        default:                    return 2;
+    }
+}
+
+float Kinematics::getMaxRPM()
+{
+    return max_rpm_;
+}
\ No newline at end of file
diff --git a/firmware/lib/kinematics/kinematics.h b/firmware/lib/kinematics/kinematics.h
new file mode 100644
index 0000000..4ddeb35
--- /dev/null
+++ b/firmware/lib/kinematics/kinematics.h
@@ -0,0 +1,69 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef KINEMATICS_H
+#define KINEMATICS_H
+
+#include "Arduino.h"
+
+#define RPM_TO_RPS 1/60
+
+class Kinematics
+{
+    public:
+        enum base {DIFFERENTIAL_DRIVE, SKID_STEER, MECANUM};
+
+        base base_platform_;
+
+        struct rpm
+        {
+            float motor1;
+            float motor2;
+            float motor3;
+            float motor4;
+        };
+        
+        struct velocities
+        {
+            float linear_x;
+            float linear_y;
+            float angular_z;
+        };
+
+        struct pwm
+        {
+            int motor1;
+            int motor2;
+            int motor3;
+            int motor4;
+        };
+        Kinematics(base robot_base, int motor_max_rpm, float max_rpm_ratio,
+                   float motor_operating_voltage, float motor_power_max_voltage,
+                   float wheel_diameter, float wheels_y_distance);
+        velocities getVelocities(float rpm1, float rpm2, float rpm3, float rpm4);
+        rpm getRPM(float linear_x, float linear_y, float angular_z);
+        float getMaxRPM();
+
+    private:
+        rpm calculateRPM(float linear_x, float linear_y, float angular_z);
+        int getTotalWheels(base robot_base);
+
+        float max_rpm_;
+        float wheels_y_distance_;
+        float pwm_res_;
+        float wheel_circumference_;
+        int total_wheels_;
+};
+
+#endif
\ No newline at end of file
diff --git a/firmware/lib/motor/default_motor.h b/firmware/lib/motor/default_motor.h
new file mode 100644
index 0000000..d160a7a
--- /dev/null
+++ b/firmware/lib/motor/default_motor.h
@@ -0,0 +1,220 @@
+// // Copyright (c) 2021 Juan Miguel Jimeno
+// //
+// // Licensed under the Apache License, Version 2.0 (the "License");
+// // you may not use this file except in compliance with the License.
+// // You may obtain a copy of the License at
+// //
+// //     http://www.apache.org/licenses/LICENSE-2.0
+// //
+// // Unless required by applicable law or agreed to in writing, software
+// // distributed under the License is distributed on an "AS IS" BASIS,
+// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// // See the License for the specific language governing permissions and
+// // limitations under the License.
+
+// #ifndef DEFAULT_MOTOR
+// #define DEFAULT_MOTOR
+
+// #include 
+// #include  
+
+// #include "motor_interface.h"
+
+// class Generic2: public MotorInterface
+// {
+//     private:
+//         int in_a_pin_;
+//         int in_b_pin_;
+//         int pwm_pin_;
+
+//     protected:
+//         void forward(int pwm) override
+//         {
+//             digitalWrite(in_a_pin_, HIGH);
+//             digitalWrite(in_b_pin_, LOW);
+//             analogWrite(pwm_pin_, abs(pwm));
+//         }
+
+//         void reverse(int pwm) override
+//         {
+//             digitalWrite(in_a_pin_, LOW);
+//             digitalWrite(in_b_pin_, HIGH);
+//             analogWrite(pwm_pin_, abs(pwm));
+//         }
+
+//     public:
+//         Generic2(float pwm_frequency, int pwm_bits, bool invert, int pwm_pin, int in_a_pin, int in_b_pin): 
+//             MotorInterface(invert),
+//             in_a_pin_(in_a_pin),
+//             in_b_pin_(in_b_pin),
+//             pwm_pin_(pwm_pin)
+//         {
+//             pinMode(in_a_pin_, OUTPUT);
+//             pinMode(in_b_pin_, OUTPUT);
+//             pinMode(pwm_pin_, OUTPUT);
+
+//             if(pwm_frequency > 0)
+//             {
+//                 // analogWriteFrequency(pwm_pin_, pwm_frequency);
+//                 analogWriteFrequency(pwm_frequency);
+//             }
+//             analogWriteResolution(pwm_bits);
+
+//             //ensure that the motor is in neutral state during bootup
+//             analogWrite(pwm_pin_, abs(0));
+//         }
+
+//         void brake() override
+//         {
+//             analogWrite(pwm_pin_, 0);
+//         }
+// };
+
+// class Generic1: public MotorInterface
+// {
+//     private:
+//         int in_pin_;
+//         int pwm_pin_;
+
+//     protected:
+//         void forward(int pwm) override
+//         {
+//             digitalWrite(in_pin_, HIGH);
+//             analogWrite(pwm_pin_, abs(pwm));
+//         }
+
+//         void reverse(int pwm) override
+//         {
+//             digitalWrite(in_pin_, LOW);
+//             analogWrite(pwm_pin_, abs(pwm));
+//         }
+
+//     public:
+//         Generic1(float pwm_frequency, int pwm_bits, bool invert, int pwm_pin, int in_pin, int unused=-1): 
+//             MotorInterface(invert),
+//             in_pin_(in_pin),
+//             pwm_pin_(pwm_pin)
+//         {
+//             pinMode(in_pin_, OUTPUT);
+//             pinMode(pwm_pin_, OUTPUT);
+
+//             if(pwm_frequency > 0)
+//             {
+//                 analogWriteFrequency(pwm_frequency);
+//             }
+//             analogWriteResolution(pwm_bits);
+
+//             //ensure that the motor is in neutral state during bootup
+//             analogWrite(pwm_pin_, abs(0));
+//         }
+
+//         void brake() override
+//         {
+//             analogWrite(pwm_pin_, 0);
+//         }
+// };
+
+// class BTS7960: public MotorInterface
+// {
+//     private:
+//         int in_a_pin_;
+//         int in_b_pin_;
+
+//     protected:
+//         void forward(int pwm) override
+//         {
+//             analogWrite(in_a_pin_, 0);
+//             analogWrite(in_b_pin_, abs(pwm));
+//         }
+
+//         void reverse(int pwm) override
+//         {
+//             analogWrite(in_b_pin_, 0);
+//             analogWrite(in_a_pin_, abs(pwm));
+//         }
+
+//     public:
+//         BTS7960(float pwm_frequency, int pwm_bits, bool invert, int unused, int in_a_pin, int in_b_pin): 
+//             MotorInterface(invert),
+//             in_a_pin_(in_a_pin),
+//             in_b_pin_(in_b_pin)
+//         {
+//             pinMode(in_a_pin_, OUTPUT);
+//             pinMode(in_b_pin_, OUTPUT);
+
+//             if(pwm_frequency > 0)
+//             {
+//                 analogWriteFrequency(pwm_frequency);
+//                 analogWriteFrequency(pwm_frequency);
+
+//             }
+//             analogWriteResolution(pwm_bits);
+
+//             //ensure that the motor is in neutral state during bootup
+//             analogWrite(in_a_pin_, 0);
+//             analogWrite(in_b_pin_, 0);
+//         }
+    
+//         BTS7960(float pwm_frequency, int pwm_bits, bool invert, int in_a_pin, int in_b_pin): 
+//             MotorInterface(invert),
+//             in_a_pin_(in_a_pin),
+//             in_b_pin_(in_b_pin)
+//         {
+//             pinMode(in_a_pin_, OUTPUT);
+//             pinMode(in_b_pin_, OUTPUT);
+
+//             if(pwm_frequency > 0)
+//             {
+//                 analogWriteFrequency(pwm_frequency);
+//                 // analogWriteFrequency(in_b_pin_, pwm_frequency);
+
+//             }
+//             analogWriteResolution(pwm_bits);
+
+//             //ensure that the motor is in neutral state during bootup
+//             analogWrite(in_a_pin_, 0);
+//             analogWrite(in_b_pin_, 0);
+//         }
+
+//         void brake() override
+//         {
+//             analogWrite(in_b_pin_, 0);
+//             analogWrite(in_a_pin_, 0);            
+//         }
+// };
+
+// class ESC: public MotorInterface
+// {
+//     private:
+//         Servo motor_;
+//         int pwm_pin_;
+
+//     protected:
+//         void forward(int pwm) override
+//         {
+//             motor_.writeMicroseconds(1500 + pwm);
+//         }
+
+//         void reverse(int pwm) override
+//         {
+//             motor_.writeMicroseconds(1500 + pwm);
+//         }
+
+//     public:
+//         ESC(float pwm_frequency, int pwm_bits, bool invert, int pwm_pin, int unused=-1, int unused2=-1): 
+//             MotorInterface(invert),
+//             pwm_pin_(pwm_pin)
+//         {
+//             motor_.attach(pwm_pin);
+            
+//             //ensure that the motor is in neutral state during bootup
+//             motor_.writeMicroseconds(1500);
+//         }
+
+//         void brake() override
+//         {
+//             motor_.writeMicroseconds(1500);         
+//         }
+// };
+
+// #endif
\ No newline at end of file
diff --git a/firmware/lib/motor/motor.h b/firmware/lib/motor/motor.h
new file mode 100644
index 0000000..cd580d1
--- /dev/null
+++ b/firmware/lib/motor/motor.h
@@ -0,0 +1,43 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef MOTOR_H
+#define MOTOR_H
+
+// include the header of your new driver here similar to default_motor.h
+#include "default_motor.h"
+
+// now you can create a config constant that you can use in lino_base_config.h
+#ifdef USE_GENERIC_2_IN_MOTOR_DRIVER
+    // pass your built in class to Motor macro
+    #define Motor Generic2
+#endif
+
+#ifdef USE_GENERIC_1_IN_MOTOR_DRIVER
+    // pass your built in class to Motor macro
+    #define Motor Generic1
+#endif
+
+#ifdef USE_BTS7960_MOTOR_DRIVER
+    // pass your built in class to Motor macro
+    #define Motor BTS7960
+#endif
+
+#ifdef USE_ESC_MOTOR_DRIVER
+    // pass your built in class to Motor macro
+    #define Motor ESC
+#endif
+
+
+#endif
diff --git a/firmware/lib/motor/motor_interface.h b/firmware/lib/motor/motor_interface.h
new file mode 100644
index 0000000..9bec92f
--- /dev/null
+++ b/firmware/lib/motor/motor_interface.h
@@ -0,0 +1,46 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef MOTOR_INTERFACE
+#define MOTOR_INTERFACE
+
+class MotorInterface
+{
+    bool invert_;
+    protected:
+        virtual void forward(int pwm) = 0;
+        virtual void reverse(int pwm) = 0;
+
+    public:
+        MotorInterface(int invert):
+            invert_(invert)
+        {
+        }
+
+        virtual void brake() = 0;
+        void spin(int pwm)
+        {
+            if(invert_)
+                pwm *= -1;
+
+            if(pwm > 0)
+                forward(pwm);
+            else if(pwm < 0)
+                reverse(pwm);
+            else
+                brake();
+        }
+};
+
+#endif
\ No newline at end of file
diff --git a/firmware/lib/odometry/odometry.cpp b/firmware/lib/odometry/odometry.cpp
new file mode 100644
index 0000000..396833e
--- /dev/null
+++ b/firmware/lib/odometry/odometry.cpp
@@ -0,0 +1,92 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "odometry.h"
+
+Odometry::Odometry():
+    x_pos_(0.0),
+    y_pos_(0.0),
+    heading_(0.0)
+{
+    odom_msg_.header.frame_id = micro_ros_string_utilities_set(odom_msg_.header.frame_id, "odom");
+    odom_msg_.child_frame_id = micro_ros_string_utilities_set(odom_msg_.child_frame_id, "base_footprint");
+}
+
+void Odometry::update(float vel_dt, float linear_vel_x, float linear_vel_y, float angular_vel_z)
+{
+    float delta_heading = angular_vel_z * vel_dt; //radians
+    float cos_h = cos(heading_);
+    float sin_h = sin(heading_);
+    float delta_x = (linear_vel_x * cos_h - linear_vel_y * sin_h) * vel_dt; //m
+    float delta_y = (linear_vel_x * sin_h + linear_vel_y * cos_h) * vel_dt; //m
+
+    //calculate current position of the robot
+    x_pos_ += delta_x;
+    y_pos_ += delta_y;
+    heading_ += delta_heading;
+
+    //calculate robot's heading in quaternion angle
+    //ROS has a function to calculate yaw in quaternion angle
+    float q[4];
+    euler_to_quat(0, 0, heading_, q);
+
+    //robot's position in x,y, and z
+    odom_msg_.pose.pose.position.x = x_pos_;
+    odom_msg_.pose.pose.position.y = y_pos_;
+    odom_msg_.pose.pose.position.z = 0.0;
+
+    //robot's heading in quaternion
+    odom_msg_.pose.pose.orientation.x = (double) q[1];
+    odom_msg_.pose.pose.orientation.y = (double) q[2];
+    odom_msg_.pose.pose.orientation.z = (double) q[3];
+    odom_msg_.pose.pose.orientation.w = (double) q[0];
+
+    odom_msg_.pose.covariance[0] = 0.001;
+    odom_msg_.pose.covariance[7] = 0.001;
+    odom_msg_.pose.covariance[35] = 0.001;
+
+    //linear speed from encoders
+    odom_msg_.twist.twist.linear.x = linear_vel_x;
+    odom_msg_.twist.twist.linear.y = linear_vel_y;
+    odom_msg_.twist.twist.linear.z = 0.0;
+
+    //angular speed from encoders
+    odom_msg_.twist.twist.angular.x = 0.0;
+    odom_msg_.twist.twist.angular.y = 0.0;
+    odom_msg_.twist.twist.angular.z = angular_vel_z;
+
+    odom_msg_.twist.covariance[0] = 0.0001;
+    odom_msg_.twist.covariance[7] = 0.0001;
+    odom_msg_.twist.covariance[35] = 0.0001;
+}
+
+nav_msgs__msg__Odometry Odometry::getData()
+{
+    return odom_msg_;
+} 
+
+const void Odometry::euler_to_quat(float roll, float pitch, float yaw, float* q) 
+{
+    float cy = cos(yaw * 0.5);
+    float sy = sin(yaw * 0.5);
+    float cp = cos(pitch * 0.5);
+    float sp = sin(pitch * 0.5);
+    float cr = cos(roll * 0.5);
+    float sr = sin(roll * 0.5);
+
+    q[0] = cy * cp * cr + sy * sp * sr;
+    q[1] = cy * cp * sr - sy * sp * cr;
+    q[2] = sy * cp * sr + cy * sp * cr;
+    q[3] = sy * cp * cr - cy * sp * sr;
+}
\ No newline at end of file
diff --git a/firmware/lib/odometry/odometry.h b/firmware/lib/odometry/odometry.h
new file mode 100644
index 0000000..bd1d3c3
--- /dev/null
+++ b/firmware/lib/odometry/odometry.h
@@ -0,0 +1,39 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef ODOMETRY_H
+#define ODOMETRY_H
+
+#include 
+#include 
+#include 
+#include 
+
+class Odometry
+{
+    public:
+        Odometry();
+        void update(float vel_dt, float linear_vel_x, float linear_vel_y, float angular_vel_z);
+        nav_msgs__msg__Odometry getData();
+
+    private:
+        const void euler_to_quat(float x, float y, float z, float* q);
+
+        nav_msgs__msg__Odometry odom_msg_;
+        float x_pos_;
+        float y_pos_;
+        float heading_;
+};
+
+#endif
\ No newline at end of file
diff --git a/firmware/lib/pid/pid.cpp b/firmware/lib/pid/pid.cpp
new file mode 100644
index 0000000..2a3ef81
--- /dev/null
+++ b/firmware/lib/pid/pid.cpp
@@ -0,0 +1,54 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "Arduino.h"
+#include "pid.h"
+
+PID::PID(float min_val, float max_val, float kp, float ki, float kd):
+    min_val_(min_val),
+    max_val_(max_val),
+    kp_(kp),
+    ki_(ki),
+    kd_(kd)
+{
+}
+
+double PID::compute(float setpoint, float measured_value)
+{
+    double error;
+    double pid;
+
+    //setpoint is constrained between min and max to prevent pid from having too much error
+    error = setpoint - measured_value;
+    integral_ += error;
+    derivative_ = error - prev_error_;
+
+    if(setpoint == 0 && error == 0)
+    {
+        integral_ = 0;
+        derivative_ = 0;
+    }
+
+    pid = (kp_ * error) + (ki_ * integral_) + (kd_ * derivative_);
+    prev_error_ = error;
+
+    return constrain(pid, min_val_, max_val_);
+}
+
+void PID::updateConstants(float kp, float ki, float kd)
+{
+    kp_ = kp;
+    ki_ = ki;
+    kd_ = kd;
+}
diff --git a/firmware/lib/pid/pid.h b/firmware/lib/pid/pid.h
new file mode 100644
index 0000000..12fb893
--- /dev/null
+++ b/firmware/lib/pid/pid.h
@@ -0,0 +1,38 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef PID_H
+#define PID_H
+
+#include "Arduino.h"
+
+class PID
+{
+    public:
+        PID(float min_val, float max_val, float kp, float ki, float kd);
+        double compute(float setpoint, float measured_value);
+        void updateConstants(float kp, float ki, float kd);
+
+    private:
+        float min_val_;
+        float max_val_;
+        float kp_;
+        float ki_;
+        float kd_;
+        double integral_;
+        double derivative_;
+        double prev_error_;
+};
+
+#endif
diff --git a/firmware/platformio.ini b/firmware/platformio.ini
new file mode 100644
index 0000000..021beaf
--- /dev/null
+++ b/firmware/platformio.ini
@@ -0,0 +1,94 @@
+; PlatformIO Project Configuration File
+;
+;   Build options: build flags, source filter
+;   Upload options: custom upload port, speed and extra flags
+;   Library options: dependencies, extra library storages
+;   Advanced options: extra scripting
+;
+; Please visit documentation for the other options and examples
+; https://docs.platformio.org/page/projectconf.html
+
+; [env]
+; platform = teensy
+; framework = arduino
+; upload_port = /dev/ttyACM0
+; upload_protocol = teensy-cli
+; board_microros_transport = serial
+; board_microros_distro = ${sysenv.ROS_DISTRO}
+; lib_deps = https://github.com/micro-ROS/micro_ros_platformio
+; build_flags = -I ../config
+
+[env:esp32doit-devkit-v1]
+platform = espressif32
+board = esp32doit-devkit-v1
+framework = arduino
+board_microros_transport = serial
+
+[env:esp32-s2-saola-1]
+platform = espressif32
+board = esp32-s2-saola-1
+monitor_speed = 115200
+framework = arduino
+board_microros_transport = serial
+;board_microros_transport = wifi
+board_microros_distro = ${sysenv.ROS_DISTRO}
+lib_deps =
+    https://github.com/micro-ROS/micro_ros_platformio
+    roboticsbrno/ServoESP32@^1.0.3
+    wollewald/MPU9250_WE@^1.2.6
+build_flags = -I ../config
+
+[env:teensy41] 
+board = teensy41
+
+[env:teensy40] 
+board = teensy40
+
+[env:teensy36]
+board = teensy36
+build_flags = 
+    -I ../config
+    -llibc -lc
+
+[env:teensy35]
+board = teensy35
+build_flags = 
+    -I ../config
+    -llibc -lc
+
+[env:teensy31] 
+board = teensy31
+board_build.f_cpu = 96000000L
+build_flags = 
+    -I ../config
+    -llibc -lc
+
+[env:dev] 
+board = teensy40
+build_flags = 
+    -I ../config
+    -D USE_DEV_CONFIG
+
+[env:beebo] 
+board = teensy31
+board_build.f_cpu = 96000000L
+build_flags = 
+    -I ../config
+    -llibc -lc
+    -D USE_BEEBO_CONFIG
+
+[env:beebo_m] 
+board = teensy31
+board_build.f_cpu = 96000000L
+build_flags = 
+    -I ../config
+    -llibc -lc
+    -D USE_BEEBO_M_CONFIG
+
+[env:square] 
+board = teensy40
+upload_port = /dev/linobase
+build_flags = 
+    -I ../config
+    -D USE_SQUARE_CONFIG
+
diff --git a/firmware/src/firmware.ino b/firmware/src/firmware.ino
new file mode 100644
index 0000000..f78fb3b
--- /dev/null
+++ b/firmware/src/firmware.ino
@@ -0,0 +1,311 @@
+// Copyright (c) 2021 Juan Miguel Jimeno
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+#include 
+#include 
+#include 
+
+#include 
+#include 
+#include 
+#include 
+
+#include 
+#include 
+#include 
+#include 
+
+#include "config.h"
+#include "motor.h"
+#include "kinematics.h"
+#include "pid.h"
+#include "odometry.h"
+#include "imu.h"
+#define ENCODER_USE_INTERRUPTS
+#define ENCODER_OPTIMIZE_INTERRUPTS
+#include "encoder.h"
+
+#define RCCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){rclErrorLoop();}}
+#define RCSOFTCHECK(fn) { rcl_ret_t temp_rc = fn; if((temp_rc != RCL_RET_OK)){}}
+#define EXECUTE_EVERY_N_MS(MS, X)  do { \
+  static volatile int64_t init = -1; \
+  if (init == -1) { init = uxr_millis();} \
+  if (uxr_millis() - init > MS) { X; init = uxr_millis();} \
+} while (0)
+
+rcl_publisher_t odom_publisher;
+rcl_publisher_t imu_publisher;
+rcl_subscription_t twist_subscriber;
+
+nav_msgs__msg__Odometry odom_msg;
+sensor_msgs__msg__Imu imu_msg;
+geometry_msgs__msg__Twist twist_msg;
+
+rclc_executor_t executor;
+rclc_support_t support;
+rcl_allocator_t allocator;
+rcl_node_t node;
+rcl_timer_t control_timer;
+
+unsigned long long time_offset = 0;
+unsigned long prev_cmd_time = 0;
+unsigned long prev_odom_update = 0;
+
+enum states 
+{
+  WAITING_AGENT,
+  AGENT_AVAILABLE,
+  AGENT_CONNECTED,
+  AGENT_DISCONNECTED
+} state;
+
+// Encoder motor1_encoder(MOTOR1_ENCODER_A, MOTOR1_ENCODER_B, COUNTS_PER_REV1, MOTOR1_ENCODER_INV);
+// Encoder motor2_encoder(MOTOR2_ENCODER_A, MOTOR2_ENCODER_B, COUNTS_PER_REV2, MOTOR2_ENCODER_INV);
+// Encoder motor3_encoder(MOTOR3_ENCODER_A, MOTOR3_ENCODER_B, COUNTS_PER_REV3, MOTOR3_ENCODER_INV);
+// Encoder motor4_encoder(MOTOR4_ENCODER_A, MOTOR4_ENCODER_B, COUNTS_PER_REV4, MOTOR4_ENCODER_INV);
+
+// Motor motor1_controller(PWM_FREQUENCY, PWM_BITS, MOTOR1_INV, MOTOR1_PWM, MOTOR1_IN_A, MOTOR1_IN_B);
+// Motor motor2_controller(PWM_FREQUENCY, PWM_BITS, MOTOR2_INV, MOTOR2_PWM, MOTOR2_IN_A, MOTOR2_IN_B);
+// Motor motor3_controller(PWM_FREQUENCY, PWM_BITS, MOTOR3_INV, MOTOR3_PWM, MOTOR3_IN_A, MOTOR3_IN_B);
+// Motor motor4_controller(PWM_FREQUENCY, PWM_BITS, MOTOR4_INV, MOTOR4_PWM, MOTOR4_IN_A, MOTOR4_IN_B);
+
+// PID motor1_pid(PWM_MIN, PWM_MAX, K_P, K_I, K_D);
+// PID motor2_pid(PWM_MIN, PWM_MAX, K_P, K_I, K_D);
+// PID motor3_pid(PWM_MIN, PWM_MAX, K_P, K_I, K_D);
+// PID motor4_pid(PWM_MIN, PWM_MAX, K_P, K_I, K_D);
+
+// Kinematics kinematics(
+//     Kinematics::LINO_BASE, 
+//     MOTOR_MAX_RPM, 
+//     MAX_RPM_RATIO, 
+//     MOTOR_OPERATING_VOLTAGE, 
+//     MOTOR_POWER_MAX_VOLTAGE, 
+//     WHEEL_DIAMETER, 
+//     LR_WHEELS_DISTANCE
+// );
+
+Odometry odometry;
+IMU imu;
+
+#define USE_SERIAL
+
+#ifdef USE_SERIAL
+    void setup() 
+    {
+        pinMode(LED_PIN, OUTPUT);
+
+        Serial.begin(115200);
+        Serial.println("Serial started");
+
+        Serial.println("Checking IMU ... ");
+        bool imu_ok = imu.init();
+        Serial.println("IMU initialized ...");
+        if(!imu_ok)
+        {
+            Serial.println("IMU not found");
+            while(1)
+            {
+                //flashLED(3);
+            }
+        }
+
+        set_microros_serial_transports(Serial);
+
+        Serial.println("Serial Connected ... ");
+        Serial.println("Connecting to MicroROS Agent ... ");
+        Serial.println("Serial Connection to MicroROS Agent established ... ");
+        Serial.println("IMU Datastream open!");
+
+
+    }
+#endif
+
+#ifdef USE_WIFI
+    void setup() 
+    {
+        pinMode(LED_PIN, OUTPUT);
+
+        Serial.begin(115200);
+        Serial.println("Serial started");
+
+        Serial.println("Checking IMU ... ");
+        bool imu_ok = imu.init();
+        Serial.println("IMU initialized ...");
+        if(!imu_ok)
+        {
+            Serial.println("IMU not found");
+            while(1)
+            {
+                //flashLED(3);
+            }
+        }
+        
+        Serial.println("Serial Connected ... ");
+
+        Serial.println("Connecting to MicroROS Agent ... ");
+        IPAddress agent_ip(192, 168, 20, 15);
+        size_t agent_port = 8888;
+
+        char ssid[] = "CPS2.4G";
+        char psk[]= "pac999CPS";
+
+        Serial.println("WiFi Connected ... ");
+        set_microros_wifi_transports(ssid, psk, agent_ip, agent_port);
+
+        Serial.println("MicroROS transport open on WiFi!");
+
+
+    }
+#endif
+
+void loop() {
+    switch (state) 
+    {
+        case WAITING_AGENT:
+            EXECUTE_EVERY_N_MS(500, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_AVAILABLE : WAITING_AGENT;);
+            break;
+        case AGENT_AVAILABLE:
+            state = (true == createEntities()) ? AGENT_CONNECTED : WAITING_AGENT;
+            if (state == WAITING_AGENT) 
+            {
+                destroyEntities();
+            }
+            break;
+        case AGENT_CONNECTED:
+            EXECUTE_EVERY_N_MS(200, state = (RMW_RET_OK == rmw_uros_ping_agent(100, 1)) ? AGENT_CONNECTED : AGENT_DISCONNECTED;);
+            if (state == AGENT_CONNECTED) 
+            {
+                rclc_executor_spin_some(&executor, RCL_MS_TO_NS(100));
+            }
+            break;
+        case AGENT_DISCONNECTED:
+            destroyEntities();
+            state = WAITING_AGENT;
+            break;
+        default:
+            break;
+    }
+}
+
+void controlCallback(rcl_timer_t * timer, int64_t last_call_time) 
+{
+    RCLC_UNUSED(last_call_time);
+    if (timer != NULL) 
+    {
+       publishData();
+    }
+}
+
+void twistCallback(const void * msgin) 
+{
+    digitalWrite(LED_PIN, !digitalRead(LED_PIN));
+
+    prev_cmd_time = millis();
+}
+
+bool createEntities()
+{
+    allocator = rcl_get_default_allocator();
+    //create init_options
+    RCCHECK(rclc_support_init(&support, 0, NULL, &allocator));
+    // create node
+    RCCHECK(rclc_node_init_default(&node, "linorobot_base_node", "", &support));
+    
+    // create IMU publisher
+    RCCHECK(rclc_publisher_init_default( 
+        &imu_publisher, 
+        &node,
+        ROSIDL_GET_MSG_TYPE_SUPPORT(sensor_msgs, msg, Imu),
+        "imu/data"
+    ));
+    
+    executor = rclc_executor_get_zero_initialized_executor();
+    RCCHECK(rclc_executor_init(&executor, &support.context, 2, & allocator));
+    RCCHECK(rclc_executor_add_timer(&executor, &control_timer));
+
+    // synchronize time with the agent
+    syncTime();
+    digitalWrite(LED_PIN, HIGH);
+
+    return true;
+}
+
+bool destroyEntities()
+{
+    rmw_context_t * rmw_context = rcl_context_get_rmw_context(&support.context);
+    (void) rmw_uros_set_context_entity_destroy_session_timeout(rmw_context, 0);
+
+    rcl_publisher_fini(&imu_publisher, &node);
+    rcl_node_fini(&node);
+    rcl_timer_fini(&control_timer);
+    rclc_executor_fini(&executor);
+    rclc_support_fini(&support);
+
+    digitalWrite(LED_PIN, HIGH);
+    
+    return true;
+}
+
+void publishData()
+{
+    imu_msg = imu.getData();
+
+    struct timespec time_stamp = getTime();
+
+    imu_msg.header.stamp.sec = time_stamp.tv_sec;
+    imu_msg.header.stamp.nanosec = time_stamp.tv_nsec;
+
+    RCSOFTCHECK(rcl_publish(&imu_publisher, &imu_msg, NULL));
+}
+
+void syncTime()
+{
+    // get the current time from the agent
+    unsigned long now = millis();
+    RCCHECK(rmw_uros_sync_session(10));
+    unsigned long long ros_time_ms = rmw_uros_epoch_millis(); 
+    // now we can find the difference between ROS time and uC time
+    time_offset = ros_time_ms - now;
+}
+
+struct timespec getTime()
+{
+    struct timespec tp = {0};
+    // add time difference between uC time and ROS time to
+    // synchronize time with ROS
+    unsigned long long now = millis() + time_offset;
+    tp.tv_sec = now / 1000;
+    tp.tv_nsec = (now % 1000) * 1000000;
+
+    return tp;
+}
+
+void rclErrorLoop() 
+{
+    while(true)
+    {
+        flashLED(2);
+    }
+}
+
+void flashLED(int n_times)
+{
+    for(int i=0; i