#include <MPU6050.h>
◆ MPU6050()
Creates an MPU6050 object.
- Note
- Default address is 0x68 Default acceleration range 2G Default gyroscope range is 250 dps (degrees per second) I2C_SDA and I2C_SCL pins are used for I2C connection by default Interrupt pin is not connected (NC) by default
- Parameters
-
retval
◆ ~MPU6050()
| virtual MPU6050::~MPU6050 |
( |
| ) |
|
|
inlinevirtual |
◆ accel()
| float * MPU6050::accel |
( |
| ) |
|
Computes acceleration.
- Note
- Parameters
-
retval
◆ calibrate()
| void MPU6050::calibrate |
( |
| ) |
|
Calibrates the MPU6050.
- Note
- Function which accumulates gyro and accelerometer data after device initialization. It calculates the average of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers.
- Parameters
-
retval
◆ dataReady()
| bool MPU6050::dataReady |
( |
| ) |
|
Indicates whether data is available after an interrupt.
- Note
- The DATA_RDY_INT bit clears to 0 after the INT_STATUS register has been read.
- Parameters
-
retval
◆ fall() [1/2]
| void MPU6050::fall |
( |
Callback< void(void)> |
func | ) |
|
◆ fall() [2/2]
| void MPU6050::fall |
( |
T * |
tptr, |
|
|
void(T::*)(void) |
mptr |
|
) |
| |
◆ gyro()
| float * MPU6050::gyro |
( |
| ) |
|
Computes gyro.
- Note
- Parameters
-
retval
◆ init()
Initializes the MPU6050.
- Note
- Parameters
-
retval
◆ lowPowerAccelOnly()
| void MPU6050::lowPowerAccelOnly |
( |
| ) |
|
Configures the motion detection control for low power accelerometer mode.
- Note
- The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out consideration for these threshold evaluations; otherwise, the flags would be set all the time!
- Parameters
-
retval
◆ madgwickFilter()
| void MPU6050::madgwickFilter |
( |
float |
deltaT | ) |
|
Madgwick filter.
- Note
- Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" (see http://www.x-io.co.uk/category/open-source/ for examples and more details) which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative device orientation – which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. The performance of the orientation filter is almost as good as conventional Kalman-based filtering algorithms but is much less computationally intensive—it can be performed on a 3.3 V Pro Mini operating at 8 MHz!
- Parameters
-
| deltaT | Integration time in seconds. |
- Return values
-
◆ pitch()
Calculates pitch in degree.
- Note
- Parameters
-
retval
◆ reset()
Resets the MPU6050.
- Note
- Parameters
-
retval
◆ rise() [1/2]
| void MPU6050::rise |
( |
Callback< void(void)> |
func | ) |
|
◆ rise() [2/2]
| void MPU6050::rise |
( |
T * |
tptr, |
|
|
void(T::*)(void) |
mptr |
|
) |
| |
◆ roll()
Claculates roll in degree.
- Note
- Parameters
-
retval
◆ selfTestOK()
| bool MPU6050::selfTestOK |
( |
| ) |
|
Performs accelerometer and gyroscope self test.
- Note
- Checks calibration wrt factory settings. Should return percent deviation from factory trim values +/- 14 or less deviation is a pass
- Parameters
-
retval true if passed false otherwise
◆ setGain()
| void MPU6050::setGain |
( |
float |
beta, |
|
|
float |
zeta |
|
) |
| |
Adjusts filter gain after device is stabilized.
- Note
- Parameters
-
retval
◆ temp()
◆ yaw()
Calculates yaw in degree.
- Note
- Parameters
-
retval
◆ accelData
| float MPU6050::accelData[3] |
◆ accelX
◆ accelY
◆ accelZ
◆ gyroData
| float MPU6050::gyroData[3] |
◆ gyroX
◆ gyroY
◆ gyroZ
The documentation for this class was generated from the following files: