MPU.hpp
Go to the documentation of this file.
1 // =========================================================================
2 // This library is placed under the MIT License
3 // Copyright 2017-2018 Natanael Josue Rabello. All rights reserved.
4 // For the license information refer to LICENSE file in root directory.
5 // =========================================================================
6 
25 #ifndef _MPU_HPP_
26 #define _MPU_HPP_
27 
28 #include <stdint.h>
29 #include "esp_err.h"
30 #include "sdkconfig.h"
31 
32 #ifdef CONFIG_MPU_I2C
33 #if !defined I2CBUS_COMPONENT_TRUE
34 #error ''MPU component requires I2Cbus library. \
35 Make sure the I2Cbus library is included in your components directory. \
36 See MPUs README.md for more information.''
37 #endif
38 
39 #include "I2Cbus.hpp"
40 
41 #elif CONFIG_MPU_SPI
42 #if !defined SPIBUS_COMPONENT_TRUE
43 #error ''MPU component requires SPIbus library. \
44 Make sure the SPIbus library is included in your components directory. \
45 See MPUs README.md for more information.''
46 #endif
47 #include "SPIbus.hpp"
48 #else
49 #error ''MPU communication protocol not specified''
50 #endif
51 
52 #include "mpu/types.hpp"
53 
55 namespace mpud {
56 class MPU;
57 }
58 
60 typedef mpud::MPU MPU_t;
61 
62 namespace mpud {
64 class MPU {
65  public:
68  MPU();
69  explicit MPU(mpu_bus_t& bus);
71  ~MPU();
75  MPU& setBus(mpu_bus_t& bus);
77  mpu_bus_t& getBus();
79  esp_err_t lastError();
83  esp_err_t initialize();
84  esp_err_t reset();
85  esp_err_t setSleep(bool enable);
86  esp_err_t testConnection();
87  esp_err_t selfTest(selftest_t* result);
88  esp_err_t resetSignalPath();
89  uint8_t whoAmI();
90  bool getSleep();
94  esp_err_t setSampleRate(uint16_t rate);
95  esp_err_t setClockSource(clock_src_t clockSrc);
96  esp_err_t setDigitalLowPassFilter(dlpf_t dlpf);
97  uint16_t getSampleRate();
103  esp_err_t setLowPowerAccelMode(bool enable);
104  esp_err_t setLowPowerAccelRate(lp_accel_rate_t rate);
106  bool getLowPowerAccelMode();
107  esp_err_t setStandbyMode(stby_en_t mask);
112  esp_err_t setGyroFullScale(gyro_fs_t fsr);
113  esp_err_t setAccelFullScale(accel_fs_t fsr);
119  esp_err_t setGyroOffset(raw_axes_t bias);
120  esp_err_t setAccelOffset(raw_axes_t bias);
123  esp_err_t computeOffsets(raw_axes_t* accel, raw_axes_t* gyro);
127  esp_err_t setInterruptConfig(int_config_t config);
128  esp_err_t setInterruptEnabled(int_en_t mask);
130  int_config_t getInterruptConfig();
135  esp_err_t setFIFOMode(fifo_mode_t mode);
136  esp_err_t setFIFOConfig(fifo_config_t config);
137  esp_err_t setFIFOEnabled(bool enable);
138  esp_err_t resetFIFO();
139  uint16_t getFIFOCount();
140  esp_err_t readFIFO(size_t length, uint8_t* data);
141  esp_err_t writeFIFO(size_t length, const uint8_t* data);
144  bool getFIFOEnabled();
148  esp_err_t setAuxI2CConfig(const auxi2c_config_t& config);
149  esp_err_t setAuxI2CEnabled(bool enable);
150  esp_err_t setAuxI2CSlaveConfig(const auxi2c_slv_config_t& config);
151  esp_err_t setAuxI2CSlaveEnabled(auxi2c_slv_t slave, bool enable);
152  esp_err_t setAuxI2CBypass(bool enable);
153  esp_err_t readAuxI2CRxData(size_t length, uint8_t* data, size_t skip = 0);
154  esp_err_t restartAuxI2C();
156  auxi2c_config_t getAuxI2CConfig();
157  auxi2c_slv_config_t getAuxI2CSlaveConfig(auxi2c_slv_t slave);
158  bool getAuxI2CEnabled();
160  bool getAuxI2CBypass();
161  esp_err_t auxI2CWriteByte(uint8_t devAddr, uint8_t regAddr, uint8_t data);
162  esp_err_t auxI2CReadByte(uint8_t devAddr, uint8_t regAddr, uint8_t* data);
166  esp_err_t setMotionDetectConfig(mot_config_t& config);
167  mot_config_t getMotionDetectConfig();
168  esp_err_t setMotionFeatureEnabled(bool enable);
170 #if defined CONFIG_MPU6000 || defined CONFIG_MPU6050 || defined CONFIG_MPU9150
171  esp_err_t setZeroMotionConfig(zrmot_config_t& config);
172  zrmot_config_t getZeroMotionConfig();
173  esp_err_t setFreeFallConfig(ff_config_t& config);
174  ff_config_t getFreeFallConfig();
176 #endif
177 #if defined CONFIG_MPU_AK89xx
181  esp_err_t compassInit();
182  esp_err_t compassTestConnection();
183  esp_err_t compassSetMode(mag_mode_t mode);
184  esp_err_t compassGetAdjustment(uint8_t* x, uint8_t* y, uint8_t* z);
186  uint8_t compassWhoAmI();
187  uint8_t compassGetInfo();
188  esp_err_t compassReadByte(uint8_t regAddr, uint8_t* data);
189  esp_err_t compassWriteByte(uint8_t regAddr, uint8_t data);
190  bool compassSelfTest(raw_axes_t* result = nullptr);
191 #endif
192 #if defined CONFIG_MPU_AK8963
193  esp_err_t compassReset();
194  esp_err_t compassSetSensitivity(mag_sensy_t sensy);
196 #endif
197  esp_err_t setFsyncConfig(int_lvl_t level);
201  esp_err_t setFsyncEnabled(bool enable);
203  bool getFsyncEnabled();
204 #if defined CONFIG_MPU6500 || defined CONFIG_MPU9250
205  esp_err_t setFchoice(fchoice_t fchoice);
207 #endif
208 #if defined CONFIG_MPU9150 || (defined CONFIG_MPU6050 && !defined CONFIG_MPU6000)
209  esp_err_t setAuxVDDIOLevel(auxvddio_lvl_t level);
211 #endif
212  esp_err_t readBit(uint8_t regAddr, uint8_t bitNum, uint8_t* data);
217  esp_err_t readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t* data);
218  esp_err_t readByte(uint8_t regAddr, uint8_t* data);
219  esp_err_t readBytes(uint8_t regAddr, size_t length, uint8_t* data);
220  esp_err_t writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data);
221  esp_err_t writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
222  esp_err_t writeByte(uint8_t regAddr, uint8_t data);
223  esp_err_t writeBytes(uint8_t regAddr, size_t length, const uint8_t* data);
224  esp_err_t registerDump(uint8_t start = 0x0, uint8_t end = 0x7F);
228  esp_err_t acceleration(raw_axes_t* accel);
229  esp_err_t acceleration(int16_t* x, int16_t* y, int16_t* z);
230  esp_err_t rotation(raw_axes_t* gyro);
231  esp_err_t rotation(int16_t* x, int16_t* y, int16_t* z);
232  esp_err_t temperature(int16_t* temp);
233  esp_err_t motion(raw_axes_t* accel, raw_axes_t* gyro);
234 #if defined CONFIG_MPU_AK89xx
235  esp_err_t heading(raw_axes_t* mag);
236  esp_err_t heading(int16_t* x, int16_t* y, int16_t* z);
237  esp_err_t motion(raw_axes_t* accel, raw_axes_t* gyro, raw_axes_t* mag);
238 #endif
239  esp_err_t sensors(raw_axes_t* accel, raw_axes_t* gyro, int16_t* temp);
240  esp_err_t sensors(sensors_t* sensors, size_t extsens_len = 0);
242 
243  protected:
244  esp_err_t accelSelfTest(raw_axes_t& regularBias, raw_axes_t& selfTestBias, uint8_t* result);
245  esp_err_t gyroSelfTest(raw_axes_t& regularBias, raw_axes_t& selfTestBias, uint8_t* result);
246  esp_err_t getBiases(accel_fs_t accelFS, gyro_fs_t gyroFS, raw_axes_t* accelBias, raw_axes_t* gyroBias,
247  bool selftest);
248 
251  uint8_t buffer[16];
252  esp_err_t err;
253 };
254 
255 } // namespace mpud
256 
257 // ==============
258 // Inline methods
259 // ==============
260 namespace mpud {
262 inline MPU::MPU() : MPU(MPU_DEFAULT_BUS) {};
273 inline MPU::MPU(mpu_bus_t& bus, mpu_addr_handle_t addr) : bus{&bus}, addr{addr}, buffer{0}, err{ESP_OK} {}
275 inline MPU::~MPU() = default;
280 inline MPU& MPU::setBus(mpu_bus_t& bus) {
281  this->bus = &bus;
282  return *this;
283 }
287 inline mpu_bus_t& MPU::getBus() { return *bus; }
293  this->addr = addr;
294  return *this;
295 }
299 inline mpu_addr_handle_t MPU::getAddr() { return addr; }
301 inline esp_err_t MPU::lastError() { return err; }
303 inline esp_err_t MPU::readBit(uint8_t regAddr, uint8_t bitNum, uint8_t* data) {
304  return err = bus->readBit(addr, regAddr, bitNum, data);
305 }
307 inline esp_err_t MPU::readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t* data) {
308  return err = bus->readBits(addr, regAddr, bitStart, length, data);
309 }
311 inline esp_err_t MPU::readByte(uint8_t regAddr, uint8_t* data) {
312  return err = bus->readByte(addr, regAddr, data);
313 }
315 inline esp_err_t MPU::readBytes(uint8_t regAddr, size_t length, uint8_t* data) {
316  return err = bus->readBytes(addr, regAddr, length, data);
317 }
319 inline esp_err_t MPU::writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data) {
320  return err = bus->writeBit(addr, regAddr, bitNum, data);
321 }
323 inline esp_err_t MPU::writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) {
324  return err = bus->writeBits(addr, regAddr, bitStart, length, data);
325 }
327 inline esp_err_t MPU::writeByte(uint8_t regAddr, uint8_t data) {
328  return err = bus->writeByte(addr, regAddr, data);
329 }
331 inline esp_err_t MPU::writeBytes(uint8_t regAddr, size_t length, const uint8_t* data) {
332  return err = bus->writeBytes(addr, regAddr, length, data);
333 }
334 
335 } // namespace mpud
336 
337 #endif /* end of include guard: _MPU_HPP_ */
auxvddio_lvl_t getAuxVDDIOLevel()
Return MPU-6050’s I/O logic levels.
Definition: MPU.cpp:1044
gyro_fs_t
Gyroscope full-scale range.
Definition: types.hpp:51
esp_err_t setMotionFeatureEnabled(bool enable)
Enable/disable Motion modules (Motion detect, Zero-motion, Free-Fall).
Definition: MPU.cpp:447
esp_err_t registerDump(uint8_t start=0x0, uint8_t end=0x7F)
Print out register values for debugging purposes.
Definition: MPU.cpp:1586
esp_err_t setAuxI2CEnabled(bool enable)
Enable / disable Auxiliary I2C Master module.
Definition: MPU.cpp:1242
esp_err_t setMotionDetectConfig(mot_config_t &config)
Configure Motion-Detect or Wake-on-motion feature.
Definition: MPU.cpp:539
bool getAuxI2CBypass()
Return Auxiliary I2C Master bypass mode state.
Definition: MPU.cpp:1369
mag_mode_t
Magnetometer operation modes.
Definition: types.hpp:515
uint8_t auxi2c_stat_t
Auxiliary I2C master status register data.
Definition: types.hpp:330
esp_err_t setStandbyMode(stby_en_t mask)
Configure sensors' standby mode.
Definition: MPU.cpp:663
mpu_i2caddr_t mpu_addr_handle_t
MPU Address/Handle type, mpu_i2caddr_t or spi_device_handle_t
Definition: types.hpp:34
esp_err_t setAccelOffset(raw_axes_t bias)
Push biases to the accel offset registers.
Definition: MPU.cpp:778
esp_err_t rotation(raw_axes_t *gyro)
Read gyroscope raw data.
Definition: MPU.cpp:898
int_config_t getInterruptConfig()
Return Interrupt pin (INT) configuration.
Definition: MPU.cpp:1072
MPU & setBus(mpu_bus_t &bus)
Set communication bus.
Definition: MPU.hpp:280
mag_mode_t compassGetMode()
Return magnetometer's measurement mode.
Definition: MPU.cpp:1811
esp_err_t writeByte(uint8_t regAddr, uint8_t data)
Write a value to a register.
Definition: MPU.hpp:327
esp_err_t setLowPowerAccelRate(lp_accel_rate_t rate)
Set Low Power Accelerometer frequency of wake-up.
Definition: MPU.cpp:413
mot_config_t getMotionDetectConfig()
Return Motion Detection Configuration.
Definition: MPU.cpp:557
mpu_addr_handle_t getAddr()
Return I2C address or SPI device handle.
Definition: MPU.hpp:299
esp_err_t setFsyncEnabled(bool enable)
Enable / disable FSYNC pin to cause an interrupt.
Definition: MPU.cpp:1569
esp_err_t compassSetMode(mag_mode_t mode)
Change magnetometer's measurement mode.
Definition: MPU.cpp:1736
lp_accel_rate_t
Low-Power Accelerometer wake-up rates.
Definition: types.hpp:104
esp_err_t setFIFOConfig(fifo_config_t config)
Configure the sensors that will be written to the FIFO.
Definition: MPU.cpp:1129
fifo_mode_t
FIFO mode.
Definition: types.hpp:430
esp_err_t setAuxI2CBypass(bool enable)
Enable / disable Auxiliary I2C bypass mode.
Definition: MPU.cpp:1346
bool getAuxI2CSlaveEnabled(auxi2c_slv_t slave)
Return enable state of a Aux I2C's Slave.
Definition: MPU.cpp:1333
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).
Definition: MPU.cpp:1498
gyro_fs_t getGyroFullScale()
Return Gyroscope Full-scale range.
Definition: MPU.cpp:718
mag_sensy_t
Magnetometer sensitivity.
Definition: types.hpp:545
dlpf_t getDigitalLowPassFilter()
Return Digital Low Pass Filter configuration.
Definition: MPU.cpp:298
esp_err_t setFsyncConfig(int_lvl_t level)
Configure the active level of FSYNC pin that will cause an interrupt.
Definition: MPU.cpp:1544
fifo_mode_t getFIFOMode()
Return FIFO mode.
Definition: MPU.cpp:1121
~MPU()
Default Destructor, does nothing.
esp_err_t readBytes(uint8_t regAddr, size_t length, uint8_t *data)
Read data from sequence of registers.
Definition: MPU.hpp:315
dlpf_t
Digital low-pass filter (based on gyro bandwidth)
Definition: types.hpp:67
bool getLowPowerAccelMode()
Return Low Power Accelerometer state.
Definition: MPU.cpp:386
esp_err_t lastError()
Return last error code.
Definition: MPU.hpp:301
esp_err_t readFIFO(size_t length, uint8_t *data)
Read data contained in FIFO buffer.
Definition: MPU.cpp:1180
auxi2c_slv_config_t getAuxI2CSlaveConfig(auxi2c_slv_t slave)
Return configuration of a Aux I2C Slave.
Definition: MPU.cpp:1300
stby_en_t getStandbyMode()
Return Standby configuration.
Definition: MPU.cpp:674
Declare Types and Definitions used within mpud namespace.
fchoice_t
Fchoice (Frequency choice maybe ?) [MPU6500 and MPU9250 only].
Definition: types.hpp:95
esp_err_t err
Holds last error code.
Definition: MPU.hpp:252
lp_accel_rate_t getLowPowerAccelRate()
Get Low Power Accelerometer frequency of wake-up.
Definition: MPU.cpp:424
esp_err_t readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data)
Read a single bit from a register.
Definition: MPU.hpp:303
uint8_t int_stat_t
Interrupt Status.
Definition: types.hpp:401
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.
Definition: MPU.cpp:2194
esp_err_t compassSetSensitivity(mag_sensy_t sensy)
Set magnetometer sensitivity.
Definition: MPU.cpp:1914
uint16_t getSampleRate()
Retrieve sample rate divider and calculate the actual rate.
Definition: MPU.cpp:245
mpu_bus_t * bus
Communication bus pointer, I2C / SPI.
Definition: MPU.hpp:249
esp_err_t readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data)
Read a range of bits from a register.
Definition: MPU.hpp:307
esp_err_t setLowPowerAccelMode(bool enable)
Enter Low Power Accelerometer mode.
Definition: MPU.cpp:342
fifo_config_t getFIFOConfig()
Return FIFO configuration.
Definition: MPU.cpp:1137
accel_fs_t
Accel full-scale range.
Definition: types.hpp:59
MPU & setAddr(mpu_addr_handle_t addr)
Set I2C address or SPI device handle.
Definition: MPU.hpp:292
uint8_t selftest_t
Self-Test results.
Definition: types.hpp:560
bool compassSelfTest(raw_axes_t *result=nullptr)
Perform Compass self-test.
Definition: MPU.cpp:1847
esp_err_t compassInit()
Initialize Magnetometer sensor.
Definition: MPU.cpp:1665
uint8_t int_en_t
Enable features to generate signal at Interrupt pin.
Definition: types.hpp:384
clock_src_t getClockSource()
Return clock source.
Definition: MPU.cpp:275
ff_config_t getFreeFallConfig()
Return Free-Fall Configuration.
Definition: MPU.cpp:637
bool getMotionFeatureEnabled()
Return true if a Motion Dectection module is enabled.
Definition: MPU.cpp:492
esp_err_t setFreeFallConfig(ff_config_t &config)
Configure Free-Fall.
Definition: MPU.cpp:619
esp_err_t setInterruptEnabled(int_en_t mask)
Enable features to generate signal at Interrupt pin.
Definition: MPU.cpp:1086
esp_err_t setAuxI2CSlaveConfig(const auxi2c_slv_config_t &config)
Configure communication with a Slave connected to Auxiliary I2C bus.
Definition: MPU.cpp:1262
esp_err_t compassWriteByte(uint8_t regAddr, uint8_t data)
Write a single byte to magnetometer.
Definition: MPU.cpp:1637
bool getAuxI2CEnabled()
Return Auxiliary I2C Master state.
Definition: MPU.cpp:1253
MPU()
Default Constructor.
Definition: MPU.hpp:262
bool getSleep()
Get current sleep state.
Definition: MPU.cpp:123
auxi2c_config_t getAuxI2CConfig()
Get Auxiliary I2C Master configuration.
Definition: MPU.cpp:1224
esp_err_t readByte(uint8_t regAddr, uint8_t *data)
Read a single register.
Definition: MPU.hpp:311
bool getFsyncEnabled()
Return FSYNC enable state.
Definition: MPU.cpp:1576
esp_err_t setZeroMotionConfig(zrmot_config_t &config)
Configure Zero-Motion.
Definition: MPU.cpp:589
static constexpr mpu_addr_handle_t MPU_DEFAULT_ADDR_HANDLE
Definition: types.hpp:36
esp_err_t heading(raw_axes_t *mag)
Read compass data.
Definition: MPU.cpp:944
clock_src_t
Clock Source.
Definition: types.hpp:83
esp_err_t writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data)
Write a range of bits to a register.
Definition: MPU.hpp:323
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).
Definition: MPU.cpp:1440
esp_err_t computeOffsets(raw_axes_t *accel, raw_axes_t *gyro)
Compute Accelerometer and Gyroscope offsets.
Definition: MPU.cpp:861
auxi2c_stat_t getAuxI2CStatus()
Return Auxiliary I2C Master status from register I2C_MST_STATUS.
Definition: MPU.cpp:1421
uint8_t compassWhoAmI()
Return value from WHO_I_AM register.
Definition: MPU.cpp:1715
static constexpr mpu_bus_t & MPU_DEFAULT_BUS
Definition: types.hpp:35
mag_sensy_t compassGetSensitivity()
Return magnetometer sensitivity.
Definition: MPU.cpp:1927
esp_err_t restartAuxI2C()
Restart Auxiliary I2C Master module, reset is asynchronous.
Definition: MPU.cpp:1415
accel_fs_t getAccelFullScale()
Return Accelerometer Full-scale range.
Definition: MPU.cpp:733
esp_err_t setAuxI2CConfig(const auxi2c_config_t &config)
Configure the Auxiliary I2C Master.
Definition: MPU.cpp:1194
esp_err_t compassReadByte(uint8_t regAddr, uint8_t *data)
Read a single byte from magnetometer.
Definition: MPU.cpp:1610
esp_err_t testConnection()
Test connection with MPU.
Definition: MPU.cpp:136
esp_err_t resetSignalPath()
Reset sensors signal path.
Definition: MPU.cpp:311
esp_err_t compassReset()
Soft reset AK8963.
Definition: MPU.cpp:1947
esp_err_t setSampleRate(uint16_t rate)
Set sample rate of data output.
Definition: MPU.cpp:178
axes_t< int16_t > raw_axes_t
Axes type to hold gyroscope, accelerometer, magnetometer raw data.
Definition: types.hpp:492
uint16_t getFIFOCount()
Return number of written bytes in the FIFO.
Definition: MPU.cpp:1171
uint8_t mot_stat_t
Motion Detection Status (MPU6000, MPU6050, MPU9150)
Definition: types.hpp:191
esp_err_t setAccelFullScale(accel_fs_t fsr)
Select Accelerometer Full-scale range.
Definition: MPU.cpp:726
esp_err_t motion(raw_axes_t *accel, raw_axes_t *gyro)
Read accelerometer and gyroscope data at once.
Definition: MPU.cpp:929
esp_err_t compassTestConnection()
Test connection with Magnetometer by checking WHO_I_AM register.
Definition: MPU.cpp:1705
esp_err_t writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data)
Write a single bit to a register.
Definition: MPU.hpp:319
auxi2c_slv_t
Auxiliary I2C Slaves slots.
Definition: types.hpp:248
esp_err_t writeBytes(uint8_t regAddr, size_t length, const uint8_t *data)
Write a sequence to data to a sequence of registers.
Definition: MPU.hpp:331
raw_axes_t getAccelOffset()
Return biases from accel offset registers.
Definition: MPU.cpp:831
raw_axes_t getGyroOffset()
Return biases from the gyro offset registers.
Definition: MPU.cpp:761
esp_err_t setFIFOMode(fifo_mode_t mode)
Change FIFO mode.
Definition: MPU.cpp:1114
esp_err_t setClockSource(clock_src_t clockSrc)
Select clock source.
Definition: MPU.cpp:268
uint8_t buffer[16]
Commom buffer for temporary data.
Definition: MPU.hpp:251
I2C_t mpu_bus_t
Communication bus type, I2Cbus or SPIbus.
Definition: types.hpp:33
uint8_t stby_en_t
Standby Mode.
Definition: types.hpp:202
mpu_bus_t & getBus()
Return communication bus object.
Definition: MPU.hpp:287
int_lvl_t
Interrupt active level.
Definition: types.hpp:349
esp_err_t setGyroFullScale(gyro_fs_t fsr)
Select Gyroscope Full-scale range.
Definition: MPU.cpp:711
fchoice_t getFchoice()
Return FCHOICE.
Definition: MPU.cpp:702
auxvddio_lvl_t
Auxiliary I2C bus VDDIO level [MPU6050 / MPU9150 only].
Definition: types.hpp:342
esp_err_t writeFIFO(size_t length, const uint8_t *data)
Write data to FIFO buffer.
Definition: MPU.cpp:1185
esp_err_t compassGetAdjustment(uint8_t *x, uint8_t *y, uint8_t *z)
Return Magnetometer's sensitivity adjustment data for each axis.
Definition: MPU.cpp:1831
esp_err_t sensors(raw_axes_t *accel, raw_axes_t *gyro, int16_t *temp)
Read data from all internal sensors.
Definition: MPU.cpp:985
esp_err_t setGyroOffset(raw_axes_t bias)
Push biases to the gyro offset registers.
Definition: MPU.cpp:746
uint8_t compassGetInfo()
Return value from magnetometer's INFO register.
Definition: MPU.cpp:1723
esp_err_t temperature(int16_t *temp)
Read temperature raw data.
Definition: MPU.cpp:920
int_en_t getInterruptEnabled()
Return enabled features configured to generate signal at Interrupt pin.
Definition: MPU.cpp:1091
Motion Processing Unit.
Definition: MPU.hpp:64
esp_err_t acceleration(raw_axes_t *accel)
Read accelerometer raw data.
Definition: MPU.cpp:876
esp_err_t reset()
Reset internal registers and restore to default start-up state.
Definition: MPU.cpp:97
mpud::MPU MPU_t
Easy alias for MPU class.
Definition: MPU.hpp:60
esp_err_t selfTest(selftest_t *result)
Trigger gyro and accel hardware self-test.
Definition: MPU.cpp:1958
esp_err_t setFchoice(fchoice_t fchoice)
Select FCHOICE.
Definition: MPU.cpp:690
esp_err_t accelSelfTest(raw_axes_t &regularBias, raw_axes_t &selfTestBias, uint8_t *result)
Accel Self-test.
Definition: MPU.cpp:2018
esp_err_t setAuxVDDIOLevel(auxvddio_lvl_t level)
The MPU-6050’s I/O logic levels are set to be either VDD or VLOGIC.
Definition: MPU.cpp:1037
int_stat_t getInterruptStatus()
Return the Interrupt status from INT_STATUS register.
Definition: MPU.cpp:1101
mot_stat_t getMotionDetectStatus()
Return Motion Detection Status.
Definition: MPU.cpp:654
uint16_t fifo_config_t
FIFO configuration, enable sensors to be written to FIFO.
Definition: types.hpp:436
esp_err_t setSleep(bool enable)
Enable / disable sleep mode.
Definition: MPU.cpp:113
bool getFIFOEnabled()
Return FIFO module state.
Definition: MPU.cpp:1154
zrmot_config_t getZeroMotionConfig()
Return Zero-Motion configuration.
Definition: MPU.cpp:598
esp_err_t setFIFOEnabled(bool enable)
Enabled / disable FIFO module.
Definition: MPU.cpp:1147
esp_err_t resetFIFO()
Reset FIFO module.
Definition: MPU.cpp:1165
esp_err_t readAuxI2CRxData(size_t length, uint8_t *data, size_t skip=0)
Read data from slaves connected to Auxiliar I2C bus.
Definition: MPU.cpp:1393
mpu_addr_handle_t addr
I2C address / SPI device handle.
Definition: MPU.hpp:250
esp_err_t setAuxI2CSlaveEnabled(auxi2c_slv_t slave, bool enable)
Enable the Auxiliary I2C module to transfer data with a slave at sample rate.
Definition: MPU.cpp:1325
int_lvl_t getFsyncConfig()
Return FSYNC pin active level configuration.
Definition: MPU.cpp:1551
uint8_t whoAmI()
Returns the value from WHO_AM_I register.
Definition: MPU.cpp:155
esp_err_t setDigitalLowPassFilter(dlpf_t dlpf)
Configures Digital Low Pass Filter (DLPF) setting for both the gyroscope and accelerometer.
Definition: MPU.cpp:284
esp_err_t setInterruptConfig(int_config_t config)
Configure the Interrupt pin (INT).
Definition: MPU.cpp:1054
esp_err_t gyroSelfTest(raw_axes_t &regularBias, raw_axes_t &selfTestBias, uint8_t *result)
Gyro Self-test.
Definition: MPU.cpp:2111
esp_err_t initialize()
Initialize MPU device and set basic configurations.
Definition: MPU.cpp:50