• Stars
    star
    229
  • Rank 174,666 (Top 4 %)
  • Language
    C++
  • License
    MIT License
  • Created over 6 years ago
  • Updated over 2 years ago

Reviews

There are no reviews yet. Be the first to send feedback to the community and the maintainers!

Repository Details

Arduino library for MPU9250 Nine-Axis (Gyro + Accelerometer + Compass) MEMS MotionTracking™ Device

MPU9250

Arduino library for MPU9250 Nine-Axis (Gyro + Accelerometer + Compass) MEMS MotionTracking™ Device

This library is based on the great work by kriswiner, and re-writen for the simple usage.

WARNING

MPU-9250 has been DISCONTINUED. I won't provide active support. This library supports only genuine MPU-9250, and I can't help other copy products of it

If you have a problem, first read the FAQ. After that, please search for similar issues. Please open the issue and fill out the issue template if you can't find the solution.

FAQ

There are interference between some axes

There are some possibilities.

  • Your device may not be a genuine MPU-9250
  • Calibration is not enough
  • Gimbal lock

Please refer #62, #69, etc.

Magnetometer is always zero

Your device may not be a genuine MPU-9250. Please refer #52 #72

Usage

Simple Measurement

#include "MPU9250.h"

MPU9250 mpu; // You can also use MPU9255 as is

void setup() {
    Serial.begin(115200);
    Wire.begin();
    delay(2000);

    mpu.setup(0x68);  // change to your own address
}

void loop() {
    if (mpu.update()) {
        Serial.print(mpu.getYaw()); Serial.print(", ");
        Serial.print(mpu.getPitch()); Serial.print(", ");
        Serial.println(mpu.getRoll());
    }
}

Calibration

  • accel/gyro/mag offsets are NOT stored to register if the MPU has powered off (app note)
  • need to set all offsets at every bootup by yourself (or calibrate at every bootup)
  • device should be stay still during accel/gyro calibration
  • round device around during mag calibration
#include "MPU9250.h"

MPU9250 mpu; // You can also use MPU9255 as is

void setup() {
    Serial.begin(115200);
    Wire.begin();
    delay(2000);

    mpu.setup(0x68);  // change to your own address

    delay(5000);

    // calibrate anytime you want to
    mpu.calibrateAccelGyro();
    mpu.calibrateMag();
}

void loop() { }

Coordinate

The coordinate of quaternion and roll/pitch/yaw angles are basedd on airplane coordinate (Right-Handed, X-forward, Z-down). On the other hand, the coordinate of euler angle is based on the axes of acceleration and gyro sensors (Right-Handed, X-forward, Z-up).Please use getEulerX/Y/Z() for euler angles and getRoll/Pitch/Yaw() for airplane coordinate angles.

Other Settings

I2C Address

You must set your own address based on A0, A1, A2 setting as:

mpu.setup(0x70);

Customize MPU9250 Configuration

You can set your own setting using MPU9250Setting struct as:

MPU9250Setting setting;
setting.accel_fs_sel = ACCEL_FS_SEL::A16G;
setting.gyro_fs_sel = GYRO_FS_SEL::G2000DPS;
setting.mag_output_bits = MAG_OUTPUT_BITS::M16BITS;
setting.fifo_sample_rate = FIFO_SAMPLE_RATE::SMPL_200HZ;
setting.gyro_fchoice = 0x03;
setting.gyro_dlpf_cfg = GYRO_DLPF_CFG::DLPF_41HZ;
setting.accel_fchoice = 0x01;
setting.accel_dlpf_cfg = ACCEL_DLPF_CFG::DLPF_45HZ;

mpu.setup(0x68, setting);

See custom_setting.ino example for detail.

List of Settings

enum class ACCEL_FS_SEL { A2G, A4G, A8G, A16G };
enum class GYRO_FS_SEL { G250DPS, G500DPS, G1000DPS, G2000DPS };
enum class MAG_OUTPUT_BITS { M14BITS, M16BITS };

enum class FIFO_SAMPLE_RATE : uint8_t {
    SMPL_1000HZ,
    SMPL_500HZ,
    SMPL_333HZ,
    SMPL_250HZ,
    SMPL_200HZ,
    SMPL_167HZ,
    SMPL_143HZ,
    SMPL_125HZ,
};

enum class GYRO_DLPF_CFG : uint8_t {
    DLPF_250HZ,
    DLPF_184HZ,
    DLPF_92HZ,
    DLPF_41HZ,
    DLPF_20HZ,
    DLPF_10HZ,
    DLPF_5HZ,
    DLPF_3600HZ,
};

enum class ACCEL_DLPF_CFG : uint8_t {
    DLPF_218HZ_0,
    DLPF_218HZ_1,
    DLPF_99HZ,
    DLPF_45HZ,
    DLPF_21HZ,
    DLPF_10HZ,
    DLPF_5HZ,
    DLPF_420HZ,
};

struct MPU9250Setting {
    ACCEL_FS_SEL     accel_fs_sel {ACCEL_FS_SEL::A16G};
    GYRO_FS_SEL      gyro_fs_sel {GYRO_FS_SEL::G2000DPS};
    MAG_OUTPUT_BITS  mag_output_bits {MAG_OUTPUT_BITS::M16BITS};
    FIFO_SAMPLE_RATE fifo_sample_rate {FIFO_SAMPLE_RATE::SMPL_200HZ};
    uint8_t          gyro_fchoice {0x03};
    GYRO_DLPF_CFG    gyro_dlpf_cfg {GYRO_DLPF_CFG::DLPF_41HZ};
    uint8_t          accel_fchoice {0x01};
    ACCEL_DLPF_CFG   accel_dlpf_cfg {ACCEL_DLPF_CFG::DLPF_45HZ};
};

Magnetic Declination

Magnetic declination should be set depending on where you are to get accurate data. To set it, use this method.

mpu.setMagneticDeclination(value);

You can find magnetic declination in your city here.

For more details, see wiki.

Quaternion Filter

You can choose quaternion filter using void selectFilter(QuatFilterSel sel). Available quaternion filters are listed below.

enum class QuatFilterSel {
    NONE,
    MADGWICK, // default
    MAHONY,
};

You can also change the calculate iterations for the filter as follows. The default value is 1. Generally 10-20 is good for stable yaw estimation. Please see this discussion for the detail.

mpu.setFilterIterations(10);

Other I2C library

You can use other I2C library e.g. SoftWire.

MPU9250_<SoftWire> mpu;
SoftWire sw(SDA, SCL);

// you need setting struct
MPU9250Setting setting;

// in setup()
mpu.setup(0x70, setting, sw);

About I2C Errors

Sometimes this library shows the I2C error number if your connection is not correct. It's based on the I2C error number which is reported by the Wire.endTransmission(). It returns following number based on the result of I2C data transmission.

0:success 1:data too long to fit in transmit buffer 2:received NACK on transmit of address 3:received NACK on transmit of data 4:other error

If you have such errors, please check your hardware connection and I2C address setting first. Please refer Wire.endTransmission() reference for these errors, and section 2.3 of this explanation for ACK and NACK.

APIs

bool setup(const uint8_t addr, const MPU9250Setting& setting, WireType& w = Wire);
void verbose(const bool b);
void ahrs(const bool b);
void sleep(bool b);
void calibrateAccelGyro();
void calibrateMag();
bool isConnected();
bool isConnectedMPU9250();
bool isConnectedAK8963();
bool isSleeping();
bool available();
bool update();
void update_accel_gyro();
void update_mag();
void update_rpy(float qw, float qx, float qy, float qz);

float getRoll() const;
float getPitch() const;
float getYaw() const;

float getEulerX() const;
float getEulerY() const;
float getEulerZ() const;

float getQuaternionX() const;
float getQuaternionY() const;
float getQuaternionZ() const;
float getQuaternionW() const;

float getAcc(const uint8_t i) const;
float getGyro(const uint8_t i) const;
float getMag(const uint8_t i) const;
float getLinearAcc(const uint8_t i) const;

float getAccX() const;
float getAccY() const;
float getAccZ() const;
float getGyroX() const;
float getGyroY() const;
float getGyroZ() const;
float getMagX() const;
float getMagY() const;
float getMagZ() const;
float getLinearAccX() const;
float getLinearAccY() const;
float getLinearAccZ() const;

float getAccBias(const uint8_t i) const;
float getGyroBias(const uint8_t i) const;
float getMagBias(const uint8_t i) const;
float getMagScale(const uint8_t i) const;

float getAccBiasX() const;
float getAccBiasY() const;
float getAccBiasZ() const;
float getGyroBiasX() const;
float getGyroBiasY() const;
float getGyroBiasZ() const;
float getMagBiasX() const;
float getMagBiasY() const;
float getMagBiasZ() const;
float getMagScaleX() const;
float getMagScaleY() const;
float getMagScaleZ() const;

float getTemperature() const;

void setAccBias(const float x, const float y, const float z);
void setGyroBias(const float x, const float y, const float z);
void setMagBias(const float x, const float y, const float z);
void setMagScale(const float x, const float y, const float z);
void setMagneticDeclination(const float d);

void selectFilter(QuatFilterSel sel);
void setFilterIterations(const size_t n);

bool selftest();

License

MIT

Acknowledgments / Contributor

More Repositories

1

ArduinoOSC

OSC subscriber / publisher for Arduino
C++
171
star
2

ArtNet

Art-Net Sender/Receiver for Arduino (Ethernet, WiFi)
C++
162
star
3

ESP32DMASPI

SPI library for ESP32 which use DMA buffer to send/receive transactions
C++
103
star
4

MsgPacketizer

msgpack based serializer / deserializer + packetize for Arduino, ROS, and more
C++
61
star
5

Tween

Tween library for Arduino with Robert Penner's easing functions
C++
41
star
6

Packetizer

binary data packetization encoder / decoder based on COBS / SLIP encoding
C++
34
star
7

MsgPack

MessagePack implementation for Arduino (compatible with other C++ apps) / msgpack.org[Arduino]
C++
33
star
8

ArxContainer

C++ container-like classes (vector, map, etc.) for Arduino which cannot use STL
C++
32
star
9

DebugLog

Logging library for Arduino that can output to both Serial and File with one line
C++
28
star
10

ArduinoEigen

Eigen (a C++ template library for linear algebra) for Arduino
C++
25
star
11

ESP32SPISlave

SPI Slave library for ESP32
C++
24
star
12

TaskManager

polling-based cooperative multi-task manager for Arduino
C++
23
star
13

MQTTPubSubClient

MQTT and MQTT over WebSoket Client for Arduino
C++
22
star
14

MCP4728

Arduino library for MCP4728 quad channel, 12-bit voltage output Digital-to-Analog Convertor with non-volatile memory and I2C compatible Serial Interface
C++
18
star
15

Dynamixel

Arduino library for Dynamixel
C++
17
star
16

Debouncer

Debounce library for Arduino
C++
14
star
17

TCS34725

Arduino library for TCS34725 RGB Color Sensor
C++
11
star
18

CRCx

CRC calculation for Arduino
C
10
star
19

TsyDMASPI

SPI library using DMA buffer for Teensy
C
10
star
20

ofxArtnetProtocol

The port of Art-Net protocol parser https://github.com/natcl/Artnet to openFrameworks and mbed.
C++
8
star
21

Filters

Filter utilities for Arduino
C++
8
star
22

L6470Stepper

L6470 / L6480 wrapper for Arduino
C++
8
star
23

FastLEDManager

My FastLED Manager that can generate multiple sequences with layered (mixed) output
C++
7
star
24

ArxTypeTraits

C++ type_traits for Arduino which cannot use it as default
C++
7
star
25

EmbeddedUtils

collections of utility headers for embedded c++
C++
6
star
26

SPIExtension

SPI extension/wrapper for Arduino
C++
6
star
27

Sony9PinRemote

RS422 Sony 9-Pin Protocol Remote Controller of VTRs for Arduino
C++
6
star
28

IM920

Interplan IM920 series wrapper for Arduino and openFrameworks
C++
5
star
29

ADS1x1x

Arduino library for ADS101x / ADS111x Ultra-Small, Low-Power, I2C-Compatible, ADCs
C++
5
star
30

MTCParser

Midi Time Code (MTC) parser
C++
5
star
31

Sketches

sketches
Rust
5
star
32

MAX17048

Arduino library for MAX17048/MAX17049 1-Cell/2-Cell Fuel Gauge with ModelGauge
C++
5
star
33

SPIDaisyChain

Daisy-chained SPI library for Arduino
C++
5
star
34

HyperDeck

BlackMagic Design HyperDeck controller for Arduino via TCP
C++
5
star
35

DRV2667

Arduino library for DRV2667 Piezo Haptic Driver with Boost, Digital Front End, and Internal Waveform Memory
C++
5
star
36

TCA9534

Arduino library for TCA9534 Low Voltage 8-Bit I2C and SMBUS Low-Power I/O Expander with Interrupt Output and Configuration Registers
C++
4
star
37

MPU6050

Arduino library for MPU-6050 Six-Axis (Gyro + Accelerometer) MEMS MotionTracking™ Devices
C++
4
star
38

PCA95x5

Arduino library for PCA9535 and PCA9555 (Remote 16-bit I2C and SMBus I/O Expander with Interrupt Output and Configuration Registers).
C++
4
star
39

ArxSmartPtr

C++ smart pointer-like classes for Arduino which can't use standard smart pointers
C++
4
star
40

PollingTimer

Arduino library to manage timing and event in a flexible way with polling
C++
4
star
41

PCA9547

Arduino library for PCA9547 (8-channel I2C-bus multiplexer with reset)
C++
4
star
42

I2CExtension

I2C extension/wrapper for Arduino
C++
3
star
43

Easing

Easing function library for Arduino
C++
3
star
44

VectorXf

Vector class 2f, 3f, 4f (port of ofVecXf (openFrameworks))
C++
3
star
45

TFmini

Arduino library for Benewake TFmini micro LiDAR module
C++
3
star
46

SceneManager

cooperative multi-scene manager for Arduino
C++
3
star
47

PCA9624

Arduino library for PCA9624 8-bit Fm+ I2C-bus 100 mA 40 V LED driver
C++
3
star
48

MsgPackRosInterfaces

ROS2 `common_interfaces` bridge based on MsgPack
C++
3
star
49

ofxSerial

Tiny extension to set options of ofSerial communication
C++
3
star
50

bevy_serial

Serial Port Communication Plugin for Bevy
Rust
2
star
51

GammaTable

Gamma Table for Arduino
C++
2
star
52

SpresenseNeoPixel

NeoPixel library for SPRESENSE (Arduino)
C++
2
star
53

ofxModbusOriental

modbus protocol wrapper for oriental motor
C++
2
star
54

pvoc-mini-plugins

Port of pvoc-plugins that can be available without LADSPA
Rust
1
star
55

rust-esp32-osc-led

Control smart LEDs from OSC via Wi-Fi on ESP32-C3
Rust
1
star
56

ES920

Arduino library for ES920/ES920LR FSK/LoRa wireless module
C++
1
star
57

hideakitai.github.io

1
star
58

hideakitai

1
star
59

rust_gui_iced_introduction

Rust
1
star
60

ArxStringUtils

Arduino String utilities
C++
1
star
61

XBeeATCmds

XBee AT Command Wrapper for Arduino
C++
1
star
62

EmbeddedApp

application template for embedded software
C++
1
star
63

TDCPlusPlusTemplate

touchdesigner CPlusPlus templates for myself
C++
1
star
64

TouchDesigner-GLSL-Sound

Template to use GLSL Sound on TouchDesigner
GLSL
1
star
65

TimeProfiler

Time profiler for Arduino
C++
1
star
66

msgpack-arduino

msgpack-c/c++ for arduino
C++
1
star
67

DS323x

Arduino library for DS3231/DS3232 Extremely Accurate I²C-Integrated RTC/TCXO/Crystal
C++
1
star
68

PCF2129

Arduino library for RTC PCF2129 with integrated quartz crystal
C++
1
star