Motion Processing Unit. More...

#include <MPU.hpp>

Inheritance diagram for mpud::MPU:
mpud::dmp::MPUdmp

Public Member Functions

Constructors / Destructor
 MPU ()
 Default Constructor. More...
 
 MPU (mpu_bus_t &bus)
 Contruct a MPU in the given communication bus. More...
 
 MPU (mpu_bus_t &bus, mpu_addr_handle_t addr)
 Construct a MPU in the given communication bus and address. More...
 
 ~MPU ()
 Default Destructor, does nothing. More...
 
Basic
MPUsetBus (mpu_bus_t &bus)
 Set communication bus. More...
 
MPUsetAddr (mpu_addr_handle_t addr)
 Set I2C address or SPI device handle. More...
 
mpu_bus_t & getBus ()
 Return communication bus object. More...
 
mpu_addr_handle_t getAddr ()
 Return I2C address or SPI device handle. More...
 
esp_err_t lastError ()
 Return last error code. More...
 
Setup
esp_err_t initialize ()
 Initialize MPU device and set basic configurations. More...
 
esp_err_t reset ()
 Reset internal registers and restore to default start-up state. More...
 
esp_err_t setSleep (bool enable)
 Enable / disable sleep mode. More...
 
esp_err_t testConnection ()
 Test connection with MPU. More...
 
esp_err_t selfTest (selftest_t *result)
 Trigger gyro and accel hardware self-test. More...
 
esp_err_t resetSignalPath ()
 Reset sensors signal path. More...
 
uint8_t whoAmI ()
 Returns the value from WHO_AM_I register. More...
 
bool getSleep ()
 Get current sleep state. More...
 
Main configurations
esp_err_t setSampleRate (uint16_t rate)
 Set sample rate of data output. More...
 
esp_err_t setClockSource (clock_src_t clockSrc)
 Select clock source. More...
 
esp_err_t setDigitalLowPassFilter (dlpf_t dlpf)
 Configures Digital Low Pass Filter (DLPF) setting for both the gyroscope and accelerometer. More...
 
uint16_t getSampleRate ()
 Retrieve sample rate divider and calculate the actual rate. More...
 
clock_src_t getClockSource ()
 Return clock source. More...
 
dlpf_t getDigitalLowPassFilter ()
 Return Digital Low Pass Filter configuration. More...
 
Power management
esp_err_t setLowPowerAccelMode (bool enable)
 Enter Low Power Accelerometer mode. More...
 
esp_err_t setLowPowerAccelRate (lp_accel_rate_t rate)
 Set Low Power Accelerometer frequency of wake-up. More...
 
lp_accel_rate_t getLowPowerAccelRate ()
 Get Low Power Accelerometer frequency of wake-up. More...
 
bool getLowPowerAccelMode ()
 Return Low Power Accelerometer state. More...
 
esp_err_t setStandbyMode (stby_en_t mask)
 Configure sensors' standby mode. More...
 
stby_en_t getStandbyMode ()
 Return Standby configuration. More...
 
Full-Scale Range
esp_err_t setGyroFullScale (gyro_fs_t fsr)
 Select Gyroscope Full-scale range. More...
 
esp_err_t setAccelFullScale (accel_fs_t fsr)
 Select Accelerometer Full-scale range. More...
 
gyro_fs_t getGyroFullScale ()
 Return Gyroscope Full-scale range. More...
 
accel_fs_t getAccelFullScale ()
 Return Accelerometer Full-scale range. More...
 
Offset / Bias
esp_err_t setGyroOffset (raw_axes_t bias)
 Push biases to the gyro offset registers. More...
 
esp_err_t setAccelOffset (raw_axes_t bias)
 Push biases to the accel offset registers. More...
 
raw_axes_t getGyroOffset ()
 Return biases from the gyro offset registers. More...
 
raw_axes_t getAccelOffset ()
 Return biases from accel offset registers. More...
 
esp_err_t computeOffsets (raw_axes_t *accel, raw_axes_t *gyro)
 Compute Accelerometer and Gyroscope offsets. More...
 
Interrupt
esp_err_t setInterruptConfig (int_config_t config)
 Configure the Interrupt pin (INT). More...
 
esp_err_t setInterruptEnabled (int_en_t mask)
 Enable features to generate signal at Interrupt pin. More...
 
int_stat_t getInterruptStatus ()
 Return the Interrupt status from INT_STATUS register. More...
 
int_config_t getInterruptConfig ()
 Return Interrupt pin (INT) configuration. More...
 
int_en_t getInterruptEnabled ()
 Return enabled features configured to generate signal at Interrupt pin. More...
 
FIFO
esp_err_t setFIFOMode (fifo_mode_t mode)
 Change FIFO mode. More...
 
esp_err_t setFIFOConfig (fifo_config_t config)
 Configure the sensors that will be written to the FIFO. More...
 
esp_err_t setFIFOEnabled (bool enable)
 Enabled / disable FIFO module. More...
 
esp_err_t resetFIFO ()
 Reset FIFO module. More...
 
uint16_t getFIFOCount ()
 Return number of written bytes in the FIFO. More...
 
esp_err_t readFIFO (size_t length, uint8_t *data)
 Read data contained in FIFO buffer. More...
 
esp_err_t writeFIFO (size_t length, const uint8_t *data)
 Write data to FIFO buffer. More...
 
fifo_mode_t getFIFOMode ()
 Return FIFO mode. More...
 
fifo_config_t getFIFOConfig ()
 Return FIFO configuration. More...
 
bool getFIFOEnabled ()
 Return FIFO module state. More...
 
Auxiliary I2C Master
esp_err_t setAuxI2CConfig (const auxi2c_config_t &config)
 Configure the Auxiliary I2C Master. More...
 
esp_err_t setAuxI2CEnabled (bool enable)
 Enable / disable Auxiliary I2C Master module. More...
 
esp_err_t setAuxI2CSlaveConfig (const auxi2c_slv_config_t &config)
 Configure communication with a Slave connected to Auxiliary I2C bus. More...
 
esp_err_t setAuxI2CSlaveEnabled (auxi2c_slv_t slave, bool enable)
 Enable the Auxiliary I2C module to transfer data with a slave at sample rate. More...
 
esp_err_t setAuxI2CBypass (bool enable)
 Enable / disable Auxiliary I2C bypass mode. More...
 
esp_err_t readAuxI2CRxData (size_t length, uint8_t *data, size_t skip=0)
 Read data from slaves connected to Auxiliar I2C bus. More...
 
esp_err_t restartAuxI2C ()
 Restart Auxiliary I2C Master module, reset is asynchronous. More...
 
auxi2c_stat_t getAuxI2CStatus ()
 Return Auxiliary I2C Master status from register I2C_MST_STATUS. More...
 
auxi2c_config_t getAuxI2CConfig ()
 Get Auxiliary I2C Master configuration. More...
 
auxi2c_slv_config_t getAuxI2CSlaveConfig (auxi2c_slv_t slave)
 Return configuration of a Aux I2C Slave. More...
 
bool getAuxI2CEnabled ()
 Return Auxiliary I2C Master state. More...
 
bool getAuxI2CSlaveEnabled (auxi2c_slv_t slave)
 Return enable state of a Aux I2C's Slave. More...
 
bool getAuxI2CBypass ()
 Return Auxiliary I2C Master bypass mode state. More...
 
esp_err_t auxI2CWriteByte (uint8_t devAddr, uint8_t regAddr, uint8_t data)
 Write to a slave a single byte just once (use for configuring a slave at initialization). More...
 
esp_err_t auxI2CReadByte (uint8_t devAddr, uint8_t regAddr, uint8_t *data)
 Read a single byte frome slave just once (use for configuring a slave at initialization). More...
 
Motion Detection Interrupt
esp_err_t setMotionDetectConfig (mot_config_t &config)
 Configure Motion-Detect or Wake-on-motion feature. More...
 
mot_config_t getMotionDetectConfig ()
 Return Motion Detection Configuration. More...
 
esp_err_t setMotionFeatureEnabled (bool enable)
 Enable/disable Motion modules (Motion detect, Zero-motion, Free-Fall). More...
 
bool getMotionFeatureEnabled ()
 Return true if a Motion Dectection module is enabled. More...
 
esp_err_t setZeroMotionConfig (zrmot_config_t &config)
 Configure Zero-Motion. More...
 
zrmot_config_t getZeroMotionConfig ()
 Return Zero-Motion configuration. More...
 
esp_err_t setFreeFallConfig (ff_config_t &config)
 Configure Free-Fall. More...
 
ff_config_t getFreeFallConfig ()
 Return Free-Fall Configuration. More...
 
mot_stat_t getMotionDetectStatus ()
 Return Motion Detection Status. More...
 
Compass | Magnetometer
esp_err_t compassInit ()
 Initialize Magnetometer sensor. More...
 
esp_err_t compassTestConnection ()
 Test connection with Magnetometer by checking WHO_I_AM register. More...
 
esp_err_t compassSetMode (mag_mode_t mode)
 Change magnetometer's measurement mode. More...
 
esp_err_t compassGetAdjustment (uint8_t *x, uint8_t *y, uint8_t *z)
 Return Magnetometer's sensitivity adjustment data for each axis. More...
 
mag_mode_t compassGetMode ()
 Return magnetometer's measurement mode. More...
 
uint8_t compassWhoAmI ()
 Return value from WHO_I_AM register. More...
 
uint8_t compassGetInfo ()
 Return value from magnetometer's INFO register. More...
 
esp_err_t compassReadByte (uint8_t regAddr, uint8_t *data)
 Read a single byte from magnetometer. More...
 
esp_err_t compassWriteByte (uint8_t regAddr, uint8_t data)
 Write a single byte to magnetometer. More...
 
bool compassSelfTest (raw_axes_t *result=nullptr)
 Perform Compass self-test. More...
 
esp_err_t compassReset ()
 Soft reset AK8963. More...
 
esp_err_t compassSetSensitivity (mag_sensy_t sensy)
 Set magnetometer sensitivity. More...
 
mag_sensy_t compassGetSensitivity ()
 Return magnetometer sensitivity. More...
 
Miscellaneous
esp_err_t setFsyncConfig (int_lvl_t level)
 Configure the active level of FSYNC pin that will cause an interrupt. More...
 
esp_err_t setFsyncEnabled (bool enable)
 Enable / disable FSYNC pin to cause an interrupt. More...
 
int_lvl_t getFsyncConfig ()
 Return FSYNC pin active level configuration. More...
 
bool getFsyncEnabled ()
 Return FSYNC enable state. More...
 
esp_err_t setFchoice (fchoice_t fchoice)
 Select FCHOICE. More...
 
fchoice_t getFchoice ()
 Return FCHOICE. More...
 
esp_err_t setAuxVDDIOLevel (auxvddio_lvl_t level)
 The MPU-6050’s I/O logic levels are set to be either VDD or VLOGIC. More...
 
auxvddio_lvl_t getAuxVDDIOLevel ()
 Return MPU-6050’s I/O logic levels. More...
 
Read / Write

Functions to perform direct read or write operation(s) to registers.

esp_err_t readBit (uint8_t regAddr, uint8_t bitNum, uint8_t *data)
 Read a single bit from a register. More...
 
esp_err_t readBits (uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data)
 Read a range of bits from a register. More...
 
esp_err_t readByte (uint8_t regAddr, uint8_t *data)
 Read a single register. More...
 
esp_err_t readBytes (uint8_t regAddr, size_t length, uint8_t *data)
 Read data from sequence of registers. More...
 
esp_err_t writeBit (uint8_t regAddr, uint8_t bitNum, uint8_t data)
 Write a single bit to a register. More...
 
esp_err_t writeBits (uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data)
 Write a range of bits to a register. More...
 
esp_err_t writeByte (uint8_t regAddr, uint8_t data)
 Write a value to a register. More...
 
esp_err_t writeBytes (uint8_t regAddr, size_t length, const uint8_t *data)
 Write a sequence to data to a sequence of registers. More...
 
esp_err_t registerDump (uint8_t start=0x0, uint8_t end=0x7F)
 Print out register values for debugging purposes. More...
 
Sensor readings
esp_err_t acceleration (raw_axes_t *accel)
 Read accelerometer raw data. More...
 
esp_err_t acceleration (int16_t *x, int16_t *y, int16_t *z)
 Read accelerometer raw data. More...
 
esp_err_t rotation (raw_axes_t *gyro)
 Read gyroscope raw data. More...
 
esp_err_t rotation (int16_t *x, int16_t *y, int16_t *z)
 Read gyroscope raw data. More...
 
esp_err_t temperature (int16_t *temp)
 Read temperature raw data. More...
 
esp_err_t motion (raw_axes_t *accel, raw_axes_t *gyro)
 Read accelerometer and gyroscope data at once. More...
 
esp_err_t heading (raw_axes_t *mag)
 Read compass data. More...
 
esp_err_t heading (int16_t *x, int16_t *y, int16_t *z)
 Read compass data. More...
 
esp_err_t motion (raw_axes_t *accel, raw_axes_t *gyro, raw_axes_t *mag)
 Read accelerometer, gyroscope, compass raw data. More...
 
esp_err_t sensors (raw_axes_t *accel, raw_axes_t *gyro, int16_t *temp)
 Read data from all internal sensors. More...
 
esp_err_t sensors (sensors_t *sensors, size_t extsens_len=0)
 Read data from all sensors, including external sensors in Aux I2C. More...
 

Protected Member Functions

esp_err_t accelSelfTest (raw_axes_t &regularBias, raw_axes_t &selfTestBias, uint8_t *result)
 Accel Self-test. More...
 
esp_err_t gyroSelfTest (raw_axes_t &regularBias, raw_axes_t &selfTestBias, uint8_t *result)
 Gyro Self-test. More...
 
esp_err_t getBiases (accel_fs_t accelFS, gyro_fs_t gyroFS, raw_axes_t *accelBias, raw_axes_t *gyroBias, bool selftest)
 Compute the Biases in regular mode and self-test mode. More...
 

Protected Attributes

mpu_bus_t * bus
 Communication bus pointer, I2C / SPI. More...
 
mpu_addr_handle_t addr
 I2C address / SPI device handle. More...
 
uint8_t buffer [16]
 Commom buffer for temporary data. More...
 
esp_err_t err
 Holds last error code. More...
 

Detailed Description

Motion Processing Unit.

Constructor & Destructor Documentation

mpud::MPU::MPU ( )
inline

Default Constructor.

mpud::MPU::MPU ( mpu_bus_t &  bus)
inlineexplicit

Contruct a MPU in the given communication bus.

Parameters
busBus protocol object of type I2Cbus or SPIbus.
mpud::MPU::MPU ( mpu_bus_t &  bus,
mpu_addr_handle_t  addr 
)
inline

Construct a MPU in the given communication bus and address.

Parameters
busBus protocol object of type I2Cbus or SPIbus.
addrI2C address (mpu_i2caddr_t) or SPI device handle (spi_device_handle_t).
mpud::MPU::~MPU ( )
inlinedefault

Default Destructor, does nothing.

Member Function Documentation

esp_err_t mpud::MPU::acceleration ( raw_axes_t *  accel)

Read accelerometer raw data.

esp_err_t mpud::MPU::acceleration ( int16_t *  x,
int16_t *  y,
int16_t *  z 
)

Read accelerometer raw data.

esp_err_t mpud::MPU::accelSelfTest ( raw_axes_t &  regularBias,
raw_axes_t &  selfTestBias,
uint8_t *  result 
)
protected

Accel Self-test.

Parameters
resultself-test error for each axis (X=bit0, Y=bit1, Z=bit2). Zero is a pass.
Note
Bias should be in 16G format for MPU6050 and 2G for MPU6500 based models.
esp_err_t mpud::MPU::auxI2CReadByte ( uint8_t  devAddr,
uint8_t  regAddr,
uint8_t *  data 
)

Read a single byte frome slave just once (use for configuring a slave at initialization).

This function uses Slave 4 to perform single transfers to the slave device on Aux I2C.
The byte will be transfered at first sample take, so when sample rate is at minimum (4 Hz) it may take up to a quarter of a second to start the transfer.

Attention
Auxiliary I2C Master must have already been configured before calling this function.
Returns
  • ESP_ERR_INVALID_STATE Auxiliary I2C Master not enabled;
  • ESP_ERR_NOT_FOUND Slave doesn't ACK the transfer;
  • ESP_FAIL Auxiliary I2C Master lost arbitration of the bus;
  • or other standard I2C driver error codes.
esp_err_t mpud::MPU::auxI2CWriteByte ( uint8_t  devAddr,
uint8_t  regAddr,
uint8_t  data 
)

Write to a slave a single byte just once (use for configuring a slave at initialization).

This function uses Slave 4 to perform single transfers to the slave device on Aux I2C.
The byte will be transfered at first sample take, so when sample rate is at minimum (4 Hz) it may take up to a quarter of a second to start the transfer.

Attention
Auxiliary I2C Master must have already been configured before calling this function.
Returns
  • ESP_ERR_INVALID_STATE: Auxiliary I2C Master not enabled;
  • ESP_ERR_NOT_FOUND: Slave doesn't ACK the transfer;
  • ESP_FAIL: Auxiliary I2C Master lost arbitration of the bus;
  • or other standard I2C driver error codes.
esp_err_t mpud::MPU::compassGetAdjustment ( uint8_t *  x,
uint8_t *  y,
uint8_t *  z 
)

Return Magnetometer's sensitivity adjustment data for each axis.

uint8_t mpud::MPU::compassGetInfo ( )

Return value from magnetometer's INFO register.

mag_mode_t mpud::MPU::compassGetMode ( )

Return magnetometer's measurement mode.

mag_sensy_t mpud::MPU::compassGetSensitivity ( )

Return magnetometer sensitivity.

esp_err_t mpud::MPU::compassInit ( )

Initialize Magnetometer sensor.

Initial configuration:

  • Mode: single measurement (permits variable sample rate).
  • Sensitivity: 0.15 uT/LSB = 16-bit output.

To disable the compass, call compassSetMode(MAG_MODE_POWER_DOWN).

esp_err_t mpud::MPU::compassReadByte ( uint8_t  regAddr,
uint8_t *  data 
)

Read a single byte from magnetometer.

How it's done:
It will check the communication protocol which the MPU is connected by.

  • I2C, Auxiliary I2C bus will set to bypass mode and the reading will be performed directly (faster).
  • SPI, the function will use Slave 4 of Auxiliary I2C bus to read the byte (slower).
esp_err_t mpud::MPU::compassReset ( )

Soft reset AK8963.

bool mpud::MPU::compassSelfTest ( raw_axes_t *  result = nullptr)

Perform Compass self-test.

Bug:
Not fully functional yet.
Todo:
Elaborate comment. Add more tries.
esp_err_t mpud::MPU::compassSetMode ( mag_mode_t  mode)

Change magnetometer's measurement mode.

Note
  • When user wants to change operation mode, transit to power-down mode first and then transit to other modes. After power-down mode is set, at least 100µs(Twat) is needed before setting another mode.
  • Setting to MAG_MODE_POWER_DOWN will disable readings from compass and disable (free) Aux I2C slaves 0 and 1. It will not disable Aux I2C Master I/F though! To enable back, use compassInit().
esp_err_t mpud::MPU::compassSetSensitivity ( mag_sensy_t  sensy)

Set magnetometer sensitivity.

Options:

  • MAG_SENSITIVITY_0_6_uT: 0.6 uT/LSB = 14-bit output
  • MAG_SENSITIVITY_0_15_uT: 0.15 uT/LSB = 16-bit output
esp_err_t mpud::MPU::compassTestConnection ( )

Test connection with Magnetometer by checking WHO_I_AM register.

uint8_t mpud::MPU::compassWhoAmI ( )

Return value from WHO_I_AM register.

Should be 0x48 for AK8963 and AK8975.

esp_err_t mpud::MPU::compassWriteByte ( uint8_t  regAddr,
uint8_t  data 
)

Write a single byte to magnetometer.

How it's done:
It will check the communication protocol which the MPU is connected by.

  • I2C, Auxiliary I2C bus will set to bypass mode and the reading will be performed directly (faster).
  • SPI, the function will use Slave 4 of Auxiliary I2C bus to read the byte (slower).
esp_err_t mpud::MPU::computeOffsets ( raw_axes_t *  accel,
raw_axes_t *  gyro 
)

Compute Accelerometer and Gyroscope offsets.

This takes about ~400ms to compute offsets. When calculating the offsets the MPU must remain as horizontal as possible (0 degrees), facing up. It is better to call computeOffsets() before any configuration is done (better right after initialize()).

Note: Gyro offset output are LSB in 1000DPS format. Note: Accel offset output are LSB in 16G format.

accel_fs_t mpud::MPU::getAccelFullScale ( )

Return Accelerometer Full-scale range.

raw_axes_t mpud::MPU::getAccelOffset ( )

Return biases from accel offset registers.

This returns the biases with OTP values from factory trim added, so returned values will be different than that ones set with setAccelOffset().

Note: Bias output are LSB in +-16G format.

mpu_addr_handle_t mpud::MPU::getAddr ( )
inline

Return I2C address or SPI device handle.

bool mpud::MPU::getAuxI2CBypass ( )

Return Auxiliary I2C Master bypass mode state.

auxi2c_config_t mpud::MPU::getAuxI2CConfig ( )

Get Auxiliary I2C Master configuration.

bool mpud::MPU::getAuxI2CEnabled ( )

Return Auxiliary I2C Master state.

auxi2c_slv_config_t mpud::MPU::getAuxI2CSlaveConfig ( auxi2c_slv_t  slave)

Return configuration of a Aux I2C Slave.

Parameters
slaveslave number.
bool mpud::MPU::getAuxI2CSlaveEnabled ( auxi2c_slv_t  slave)

Return enable state of a Aux I2C's Slave.

auxi2c_stat_t mpud::MPU::getAuxI2CStatus ( )

Return Auxiliary I2C Master status from register I2C_MST_STATUS.

Reading this register clear all its bits.

auxvddio_lvl_t mpud::MPU::getAuxVDDIOLevel ( )

Return MPU-6050’s I/O logic levels.

esp_err_t mpud::MPU::getBiases ( accel_fs_t  accelFS,
gyro_fs_t  gyroFS,
raw_axes_t *  accelBias,
raw_axes_t *  gyroBias,
bool  selftest 
)
protected

Compute the Biases in regular mode and self-test mode.

Attention
When calculating the biases the MPU must remain as horizontal as possible (0 degrees), facing up. This algorithm takes about ~400ms to compute offsets.
mpu_bus_t & mpud::MPU::getBus ( )
inline

Return communication bus object.

clock_src_t mpud::MPU::getClockSource ( )

Return clock source.

dlpf_t mpud::MPU::getDigitalLowPassFilter ( )

Return Digital Low Pass Filter configuration.

fchoice_t mpud::MPU::getFchoice ( )

Return FCHOICE.

fifo_config_t mpud::MPU::getFIFOConfig ( )

Return FIFO configuration.

uint16_t mpud::MPU::getFIFOCount ( )

Return number of written bytes in the FIFO.

Note
FIFO overflow generates an interrupt which can be check with getInterruptStatus().
bool mpud::MPU::getFIFOEnabled ( )

Return FIFO module state.

fifo_mode_t mpud::MPU::getFIFOMode ( )

Return FIFO mode.

ff_config_t mpud::MPU::getFreeFallConfig ( )

Return Free-Fall Configuration.

int_lvl_t mpud::MPU::getFsyncConfig ( )

Return FSYNC pin active level configuration.

bool mpud::MPU::getFsyncEnabled ( )

Return FSYNC enable state.

gyro_fs_t mpud::MPU::getGyroFullScale ( )

Return Gyroscope Full-scale range.

raw_axes_t mpud::MPU::getGyroOffset ( )

Return biases from the gyro offset registers.

Note: Bias output are LSB in +-1000dps format.

int_config_t mpud::MPU::getInterruptConfig ( )

Return Interrupt pin (INT) configuration.

int_en_t mpud::MPU::getInterruptEnabled ( )

Return enabled features configured to generate signal at Interrupt pin.

int_stat_t mpud::MPU::getInterruptStatus ( )

Return the Interrupt status from INT_STATUS register.

Note: Reading this register, clear all bits.

bool mpud::MPU::getLowPowerAccelMode ( )

Return Low Power Accelerometer state.

Condition to return true:

  • CYCLE bit is 1
  • SLEEP bit is 0
  • TEMP_DIS bit is 1
  • STBY_XG, STBY_YG, STBY_ZG bits are 1
  • STBY_XA, STBY_YA, STBY_ZA bits are 0
  • FCHOICE is 0 (ACCEL_FCHOICE_B bit is 1) [MPU6500 / MPU9250 only]
lp_accel_rate_t mpud::MPU::getLowPowerAccelRate ( )

Get Low Power Accelerometer frequency of wake-up.

mot_config_t mpud::MPU::getMotionDetectConfig ( )

Return Motion Detection Configuration.

mot_stat_t mpud::MPU::getMotionDetectStatus ( )

Return Motion Detection Status.

Note
Reading this register clears all motion detection status bits.
bool mpud::MPU::getMotionFeatureEnabled ( )

Return true if a Motion Dectection module is enabled.

uint16_t mpud::MPU::getSampleRate ( )

Retrieve sample rate divider and calculate the actual rate.

bool mpud::MPU::getSleep ( )

Get current sleep state.

Returns
  • true: sleep enabled.
  • false: sleep disabled.
stby_en_t mpud::MPU::getStandbyMode ( )

Return Standby configuration.

zrmot_config_t mpud::MPU::getZeroMotionConfig ( )

Return Zero-Motion configuration.

esp_err_t mpud::MPU::gyroSelfTest ( raw_axes_t &  regularBias,
raw_axes_t &  selfTestBias,
uint8_t *  result 
)
protected

Gyro Self-test.

Parameters
resultSelf-test error for each axis (X=bit0, Y=bit1, Z=bit2). Zero is a pass.
Note
Bias should be in 250DPS format for both MPU6050 and MPU6500 based models.
esp_err_t mpud::MPU::heading ( raw_axes_t *  mag)

Read compass data.

esp_err_t mpud::MPU::heading ( int16_t *  x,
int16_t *  y,
int16_t *  z 
)

Read compass data.

esp_err_t mpud::MPU::initialize ( )

Initialize MPU device and set basic configurations.

Init configuration:

  • Accel FSR: 4G
  • Gyro FSR: 500DPS
  • Sample rate: 100Hz
  • DLPF: 42Hz
  • INT pin: disabled
  • FIFO: disabled
  • Clock source: gyro PLL
    For MPU9150 and MPU9250:
  • Aux I2C Master: enabled, clock: 400KHz
  • Compass: enabled on Aux I2C's Slave 0 and Slave 1
Note
  • A soft reset is performed first, which takes 100-200ms.
  • When using SPI, the primary I2C Slave module is disabled right away.
esp_err_t mpud::MPU::lastError ( )
inline

Return last error code.

esp_err_t mpud::MPU::motion ( raw_axes_t *  accel,
raw_axes_t *  gyro 
)

Read accelerometer and gyroscope data at once.

esp_err_t mpud::MPU::motion ( raw_axes_t *  accel,
raw_axes_t *  gyro,
raw_axes_t *  mag 
)

Read accelerometer, gyroscope, compass raw data.

esp_err_t mpud::MPU::readAuxI2CRxData ( size_t  length,
uint8_t *  data,
size_t  skip = 0 
)

Read data from slaves connected to Auxiliar I2C bus.

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.

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.

Attention
Set skip to 8 when using compass, because compass data takes up the first 8 bytes.
esp_err_t mpud::MPU::readBit ( uint8_t  regAddr,
uint8_t  bitNum,
uint8_t *  data 
)
inline

Read a single bit from a register.

esp_err_t mpud::MPU::readBits ( uint8_t  regAddr,
uint8_t  bitStart,
uint8_t  length,
uint8_t *  data 
)
inline

Read a range of bits from a register.

esp_err_t mpud::MPU::readByte ( uint8_t  regAddr,
uint8_t *  data 
)
inline

Read a single register.

esp_err_t mpud::MPU::readBytes ( uint8_t  regAddr,
size_t  length,
uint8_t *  data 
)
inline

Read data from sequence of registers.

esp_err_t mpud::MPU::readFIFO ( size_t  length,
uint8_t *  data 
)

Read data contained in FIFO buffer.

esp_err_t mpud::MPU::registerDump ( uint8_t  start = 0x0,
uint8_t  end = 0x7F 
)

Print out register values for debugging purposes.

Parameters
startfirst register number.
endlast register number.
esp_err_t mpud::MPU::reset ( )

Reset internal registers and restore to default start-up state.

Note
  • This function delays 100ms when using I2C and 200ms when using SPI.
  • It does not initialize the MPU again, just call initialize() instead.
esp_err_t mpud::MPU::resetFIFO ( )

Reset FIFO module.

Zero FIFO count, reset is asynchronous.
The bit auto clears after one clock cycle.

esp_err_t mpud::MPU::resetSignalPath ( )

Reset sensors signal path.

Reset all gyro digital signal path, accel digital signal path, and temp digital signal path. This also clears all the sensor registers.

Note
This function delays 100 ms, needed for reset to complete.
esp_err_t mpud::MPU::restartAuxI2C ( )

Restart Auxiliary I2C Master module, reset is asynchronous.

This bit (I2C_MST_RST) should only be set when the I2C master has hung. If this bit is set during an active I2C master transaction, the I2C slave will hang, which will require the host to reset the slave.

esp_err_t mpud::MPU::rotation ( raw_axes_t *  gyro)

Read gyroscope raw data.

esp_err_t mpud::MPU::rotation ( int16_t *  x,
int16_t *  y,
int16_t *  z 
)

Read gyroscope raw data.

esp_err_t mpud::MPU::selfTest ( selftest_t *  result)

Trigger gyro and accel hardware self-test.

Attention
when calling this function, the MPU must remain as horizontal as possible (0 degrees), facing up.
Parameters
resultShould be ZERO if gyro and accel passed.
Todo:
Elaborate doc.
esp_err_t mpud::MPU::sensors ( raw_axes_t *  accel,
raw_axes_t *  gyro,
int16_t *  temp 
)

Read data from all internal sensors.

esp_err_t mpud::MPU::sensors ( sensors_t *  sensors,
size_t  extsens_len = 0 
)

Read data from all sensors, including external sensors in Aux I2C.

esp_err_t mpud::MPU::setAccelFullScale ( accel_fs_t  fsr)

Select Accelerometer Full-scale range.

esp_err_t mpud::MPU::setAccelOffset ( raw_axes_t  bias)

Push biases to the accel offset registers.

This function expects biases relative to the current sensor output, and these biases will be added to the factory-supplied values.

Note: Bias inputs are LSB in +-16G format.

MPU & mpud::MPU::setAddr ( mpu_addr_handle_t  addr)
inline

Set I2C address or SPI device handle.

Parameters
addrI2C address (mpu_i2caddr_t) or SPI device handle (spi_device_handle_t).
esp_err_t mpud::MPU::setAuxI2CBypass ( bool  enable)

Enable / disable Auxiliary I2C bypass mode.

Parameters
enable
  • true: Auxiliar I2C Master I/F is disabled, and Bypass enabled.
  • false: Bypass is disabled, but the Auxiliar I2C Master I/F is not enabled back, if needed, enabled it again with setAuxI2CmasterEnabled().
esp_err_t mpud::MPU::setAuxI2CConfig ( const auxi2c_config_t &  config)

Configure the Auxiliary I2C Master.

Note
For [MPU9150, MPU9250]: The Auxiliary I2C is configured in the initialization stage to connect with the compass in Slave 0 and Slave 1.
esp_err_t mpud::MPU::setAuxI2CEnabled ( bool  enable)

Enable / disable Auxiliary I2C Master module.

esp_err_t mpud::MPU::setAuxI2CSlaveConfig ( const auxi2c_slv_config_t &  config)

Configure communication with a Slave connected to Auxiliary I2C bus.

esp_err_t mpud::MPU::setAuxI2CSlaveEnabled ( auxi2c_slv_t  slave,
bool  enable 
)

Enable the Auxiliary I2C module to transfer data with a slave at sample rate.

esp_err_t mpud::MPU::setAuxVDDIOLevel ( auxvddio_lvl_t  level)

The MPU-6050’s I/O logic levels are set to be either VDD or VLOGIC.

VLOGIC may be set to be equal to VDD or to another voltage. However, VLOGIC must be ≤ VDD at all times. When AUX_VDDIO is set to 0 (its power-on-reset value), VLOGIC is the power supply voltage for both the microprocessor system bus and the auxiliary I C bus. When AUX_VDDIO is set to 1, VLOGIC is the power supply voltage for the microprocessor system bus and VDD is the supply for the auxiliary I2C bus

MPU & mpud::MPU::setBus ( mpu_bus_t &  bus)
inline

Set communication bus.

Parameters
busBus protocol object of type I2Cbus or SPIbus.
esp_err_t mpud::MPU::setClockSource ( clock_src_t  clockSrc)

Select clock source.

Note
The gyro PLL is better than internal clock.
Parameters
clockSrcclock source
esp_err_t mpud::MPU::setDigitalLowPassFilter ( dlpf_t  dlpf)

Configures Digital Low Pass Filter (DLPF) setting for both the gyroscope and accelerometer.

Parameters
dlpfdigital low-pass filter value
esp_err_t mpud::MPU::setFchoice ( fchoice_t  fchoice)

Select FCHOICE.

Dev note: FCHOICE is the inverted value of FCHOICE_B (e.g. FCHOICE=2b’00 is same as FCHOICE_B=2b’11). Reset value is FCHOICE_3

esp_err_t mpud::MPU::setFIFOConfig ( fifo_config_t  config)

Configure the sensors that will be written to the FIFO.

esp_err_t mpud::MPU::setFIFOEnabled ( bool  enable)

Enabled / disable FIFO module.

esp_err_t mpud::MPU::setFIFOMode ( fifo_mode_t  mode)

Change FIFO mode.

Options: FIFO_MODE_OVERWRITE: When the fifo is full, additional writes will be written to the fifo,replacing the oldest data. FIFO_MODE_STOP_FULL: When the fifo is full, additional writes will not be written to fifo.

esp_err_t mpud::MPU::setFreeFallConfig ( ff_config_t &  config)

Configure Free-Fall.

Free fall is detected by checking if the accelerometer measurements from all 3 axes have an absolute value below a user-programmable threshold (acceleration threshold). For each sample where this condition is true (a qualifying sample), a counter is incremented. For each sample where this condition is false (a non- qualifying sample), the counter is decremented. Once the counter reaches a user-programmable threshold (the counter threshold), the Free Fall interrupt is triggered and a flag is set. The flag is cleared once the counter has decremented to zero. The counter does not increment above the counter threshold or decrement below zero.

Note
Enable by calling setMotionFeatureEnabled().
esp_err_t mpud::MPU::setFsyncConfig ( int_lvl_t  level)

Configure the active level of FSYNC pin that will cause an interrupt.

Use setFsyncEnabled() to enable / disable this interrupt.

esp_err_t mpud::MPU::setFsyncEnabled ( bool  enable)

Enable / disable FSYNC pin to cause an interrupt.

Note
  • The interrupt status is located in I2C_MST_STATUS register, so use the method getAuxI2CStatus() which reads this register to get FSYNC status. Keep in mind that a read from I2C_MST_STATUS register clears all its status bits, so take care to miss status bits when using Auxiliary I2C bus too.
  • It is possible to enable the FSYNC interrupt propagate to INT pin with setInterruptEnabled(), then the status can also be read with getInterruptStatus().
See Also
setFsyncConfig().
esp_err_t mpud::MPU::setGyroFullScale ( gyro_fs_t  fsr)

Select Gyroscope Full-scale range.

esp_err_t mpud::MPU::setGyroOffset ( raw_axes_t  bias)

Push biases to the gyro offset registers.

This function expects biases relative to the current sensor output, and these biases will be added to the factory-supplied values.

Note: Bias inputs are LSB in +-1000dps format.

esp_err_t mpud::MPU::setInterruptConfig ( int_config_t  config)

Configure the Interrupt pin (INT).

Parameters
configconfiguration desired.
esp_err_t mpud::MPU::setInterruptEnabled ( int_en_t  mask)

Enable features to generate signal at Interrupt pin.

Parameters
maskORed features.
esp_err_t mpud::MPU::setLowPowerAccelMode ( bool  enable)

Enter Low Power Accelerometer mode.

In low-power accel mode, the chip goes to sleep and only wakes up to sample the accelerometer at a certain frequency. See setLowPowerAccelRate() to set the frequency.

Parameters
enablevalue
  • This function does the following to enable:
    • Set CYCLE bit to 1
    • Set SLEEP bit to 0
    • Set TEMP_DIS bit to 1
    • Set STBY_XG, STBY_YG, STBY_ZG bits to 1
    • Set STBY_XA, STBY_YA, STBY_ZA bits to 0
    • Set FCHOICE to 0 (ACCEL_FCHOICE_B bit to 1) [MPU6500 / MPU9250 only]
    • Disable Auxiliary I2C Master I/F
  • This function does the following to disable:
    • Set CYCLE bit to 0
    • Set TEMP_DIS bit to 0
    • Set STBY_XG, STBY_YG, STBY_ZG bits to 0
    • Set STBY_XA, STBY_YA, STBY_ZA bits to 0
    • Set FCHOICE to 3 (ACCEL_FCHOICE_B bit to 0) [MPU6500 / MPU9250 only]
    • Enable Auxiliary I2C Master I/F
esp_err_t mpud::MPU::setLowPowerAccelRate ( lp_accel_rate_t  rate)

Set Low Power Accelerometer frequency of wake-up.

esp_err_t mpud::MPU::setMotionDetectConfig ( mot_config_t &  config)

Configure Motion-Detect or Wake-on-motion feature.

The behaviour of this feature is very different between the MPU6050 (MPU9150) and the MPU6500 (MPU9250). Each chip's version of this feature is explained below.

[MPU6050, MPU6000, MPU9150]: Accelerometer measurements are passed through a configurable digital high pass filter (DHPF) in order to eliminate bias due to gravity. A qualifying motion sample is one where the high passed sample from any axis has an absolute value exceeding a user-programmable threshold. A counter increments for each qualifying sample, and decrements for each non-qualifying sample. Once the counter reaches a user-programmable counter threshold, a motion interrupt is triggered. The axis and polarity which caused the interrupt to be triggered is flagged in the MOT_DETECT_STATUS register.

[MPU6500, MPU9250]: Unlike the MPU6050 version, the hardware does not "lock in" a reference sample. The hardware monitors the accel data and detects any large change over a short period of time. A qualifying motion sample is one where the high passed sample from any axis has an absolute value exceeding the threshold. The hardware motion threshold can be between 4mg and 1020mg in 4mg increments.

Note
It is possible to enable wake-on-motion mode by doing the following:
  1. Enter Low Power Accelerometer mode with setLowPowerAccelMode();
  2. Select the wake-up rate with setLowPowerAccelRate();
  3. Configure motion-detect interrupt with setMotionDetectConfig();
  4. Enable the motion detection module with setMotionFeatureEnabled();
esp_err_t mpud::MPU::setMotionFeatureEnabled ( bool  enable)

Enable/disable Motion modules (Motion detect, Zero-motion, Free-Fall).

Attention
The configurations must've already been set with setMotionDetectConfig() before enabling the module!
Note
  • Call getMotionDetectStatus() to find out which axis generated motion interrupt. [MPU6000, MPU6050, MPU9150].
  • It is recommended to set the Motion Interrupt to propagate to the INT pin. To do that, use setInterruptEnabled().
Parameters
enable
  • On true, this function modifies the DLPF, put gyro and temperature in standby, and disable Auxiliary I2C Master I/F.
  • On false, this function sets DLPF to 42Hz and enables Auxiliary I2C master I/F.
esp_err_t mpud::MPU::setSampleRate ( uint16_t  rate)

Set sample rate of data output.

Sample rate controls sensor data output rate and FIFO sample rate. This is the update rate of sensor register.
Formula: Sample Rate = Internal Output Rate / (1 + SMPLRT_DIV)

Parameters
rate4Hz ~ 1KHz
  • For sample rate 8KHz: set digital low pass filter to DLPF_256HZ_NOLPF.
  • For sample rate 32KHZ [MPU6500 / MPU9250]: set fchoice to FCHOICE_0, see setFchoice().
Note
For MPU9150 & MPU9250:
  • When using compass, this function alters Aux I2C Master sample_delay property to adjust the compass sample rate. (also, wait_for_es property to adjust interrupt).
  • If sample rate lesser than 100 Hz, data-ready interrupt will wait for compass data.
  • If sample rate greater than 100 Hz, data-ready interrupt will not be delayed by the compass.
esp_err_t mpud::MPU::setSleep ( bool  enable)

Enable / disable sleep mode.

Parameters
enableenable value
esp_err_t mpud::MPU::setStandbyMode ( stby_en_t  mask)

Configure sensors' standby mode.

esp_err_t mpud::MPU::setZeroMotionConfig ( zrmot_config_t &  config)

Configure Zero-Motion.

The Zero Motion detection capability uses the digital high pass filter (DHPF) and a similar threshold scheme to that of Free Fall detection. Each axis of the high passed accelerometer measurement must have an absolute value less than a threshold specified in the ZRMOT_THR register, which can be increased in 1 mg increments. Each time a motion sample meets this condition, a counter increments. When this counter reaches a threshold specified in ZRMOT_DUR, an interrupt is generated.

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. While Free Fall and Motion are indicated with a flag which clears after being read, reading the state of the Zero Motion detected from the MOT_DETECT_STATUS register does not clear its status.

Note
Enable by calling setMotionFeatureEnabled();
esp_err_t mpud::MPU::temperature ( int16_t *  temp)

Read temperature raw data.

esp_err_t mpud::MPU::testConnection ( )

Test connection with MPU.

It reads the WHO_AM_IM register and check its value against the correct chip model.

Returns
  • ESP_OK: The MPU is connected and matchs the model.
  • ESP_ERR_NOT_FOUND: A device is connect, but does not match the chip selected in menuconfig.
  • May return other communication bus errors. e.g: ESP_FAIL, ESP_ERR_TIMEOUT.
uint8_t mpud::MPU::whoAmI ( )

Returns the value from WHO_AM_I register.

esp_err_t mpud::MPU::writeBit ( uint8_t  regAddr,
uint8_t  bitNum,
uint8_t  data 
)
inline

Write a single bit to a register.

esp_err_t mpud::MPU::writeBits ( uint8_t  regAddr,
uint8_t  bitStart,
uint8_t  length,
uint8_t  data 
)
inline

Write a range of bits to a register.

esp_err_t mpud::MPU::writeByte ( uint8_t  regAddr,
uint8_t  data 
)
inline

Write a value to a register.

esp_err_t mpud::MPU::writeBytes ( uint8_t  regAddr,
size_t  length,
const uint8_t *  data 
)
inline

Write a sequence to data to a sequence of registers.

esp_err_t mpud::MPU::writeFIFO ( size_t  length,
const uint8_t *  data 
)

Write data to FIFO buffer.

Member Data Documentation

mpu_addr_handle_t mpud::MPU::addr
protected

I2C address / SPI device handle.

uint8_t mpud::MPU::buffer[16]
protected

Commom buffer for temporary data.

mpu_bus_t* mpud::MPU::bus
protected

Communication bus pointer, I2C / SPI.

esp_err_t mpud::MPU::err
protected

Holds last error code.


The documentation for this class was generated from the following files:
  • /home/travis/build/natanaeljr/esp32-MPU-driver/include/MPU.hpp
  • /home/travis/build/natanaeljr/esp32-MPU-driver/src/MPU.cpp