Giter VIP home page Giter VIP logo

sparkfun_mpu-9250-dmp_arduino_library's Introduction

SparkFun MPU-9250 Digital Motion Processor (DMP) Arduino Library

SparkFun MPU-9250

SparkFun MPU-9250 (SEN-13762)

Advanced Arduino library for the Invensense MPU-9250 inertial measurement unit (IMU), which enables the sensor's digital motion processing (DMP) features. Along with configuring and reading from the accelerometer, gyroscope, and magnetometer, this library also supports the chip's DMP features like:

  • Quaternion calculation
  • Pedometer
  • Gyroscope calibration
  • Tap detection
  • Orientation dtection

For help getting started with this library, refer to the Using the MPU-9250 DMP Arduino Library section of the 9DoF Razor IMU M0 Hookup Guide.

Note: This library currently only supports and is tested on SAMD processors. It's a major part of the SparkFun 9DoF Razor IMU M0 firmware.

If you're looking for an AVR-compatible (Arduino Uno, SparkFun RedBoard, etc.) library, check out the SparkFun MPU-9250 Breakout Library, which provides access to all standard MPU-9250 sensor-readings.

Repository Contents

  • /examples - Example sketches for the library (.ino). Run these from the Arduino IDE.
  • /src - Source files for the library (.cpp, .h).
    • /src/util - Source and headers for the MPU-9250 driver and dmp configuration. These are available and adapted from Invensene's downloads page.
  • keywords.txt - Keywords from this library that will be highlighted in the Arduino IDE.
  • library.properties - General library properties for the Arduino package manager.

Documentation

Products that use this Library

Version History

License Information

This product is open source!

Please review the LICENSE.md file for license information.

If you have any questions or concerns on licensing, please contact [email protected].

Distributed as-is; no warranty is given.

  • Your friends at SparkFun.

sparkfun_mpu-9250-dmp_arduino_library's People

Contributors

bhagman avatar jimblom avatar loricrotser avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

sparkfun_mpu-9250-dmp_arduino_library's Issues

MPU9250 I2C Address

Hi, where is the MPU-9250 I2C Address of 0x68 defined, I can't find it? I need to set it to 0x69; the ADO pin, in my case, is set to 1 (HIGH).

Arduino Micro Tap Detection and Wake On Motion (I2C)

Hello,

i am trying to program a little "LED-Cube", battery powered, wirelessly charged and not accessible from outside.

The MPU9250 and Atmega32u4 are already used, so not really easy to use other boards.

I am thinking about the following:

The Atmega32u4 should control a bunch of WS2812 LEDs, that code works (controls color depending on the orientation of the cube (on what face it rests))

now my problem, I hope someone is able to help me, is as follows:

0.: Atmega32u4 has constant battery voltage.

1.: Atmega32u4 should wake up when the cube is moved

2.: Atmega32u4 activates WS2812 LEDs with FET, sends Data.

"2.5:" if possible it should increment/decrement a counter (1....127) for brightness of the LEDs (use magnetometer?)

3.: Atmega32u4 turns of FET for LEDs, then should deactivate all possible sensors in MPU9250 and then go in sleep if I double-tap the cube. It should be able to wake on motion again (1.)

maybe someone can help me with this issue and provide me a little bit of help to get that running.

current status:

the cube controls its own colors depending on its orientation, so that piece is working correctly.

qToFloat mask bits default to short

on line 618 of src/SparkFunMPU9250-DMP.cpp, in my implementation (Arduino 1.6.5, Atmega32U4 Pro Micro) the variable is assumed to be a uint16_t and causes undesirable behavior when q>15. probably should be specified as unsigned long.

output from loop with q=16:
1
3
7
F
1F
3F
7F
FF
1FF
3FF
7FF
FFF
1FFF
3FFF
7FFF
FFFFFFFF

Unable to get raw accelerometer data after calculating quaternion

Hello, I am facing a problem getting raw accelerometer data. I need to substract the gravity from my raw accel data,so I am calculating my quaternions with DPM. My code is the following

  float q0 = imu.calcQuat(imu.qw);
  float q1 = imu.calcQuat(imu.qx);
  float q2 = imu.calcQuat(imu.qy);
  float q3 = imu.calcQuat(imu.qz);

  Serial.println("Q: " + String(q0, 4) + ", " + String(q1, 4) + ", " + String(q2, 4) + ", " + String(q3, 4));
  float g0,g1,g2 = 0;

  g0 = 2 * (q1 * q3 - q0 * q2);
  g1 = 2 * (q0 * q1 - q2 * q3);
  g2 = q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3;

  ax =  imu.calcAccel(imu.ay);
  ay =  imu.calcAccel(imu.ay);
  az =  imu.calcAccel(imu.az);

  cax =  (9.8 * ax - g0);
  cay =  (9.8 * ay - g1);
  caz =  (9.8 * az - g2);
  Serial.println("A: " + String(g0, 4) + ", " + String(g1, 4) + ", " + String(g2, 4) );

Im using the DPM Quaternion example and made those modifications, but my ax, ay and Az values are zero. The main loop it's exactly the one from the example, I only removed the call to computeEulerAngles() because I do not need it. I think Im not understanding exactly how to get the raw data, because the basic example is different, also I know understand that the dpm code utilizes a FIFO Buffer to store the data. I need to get the raw AY,AY and AZ values that were used to calculate the quaternion. Am I doing something wrong?

Thank you

Mystical oddities with the MPU9250 and the library

Used stm32f401ccu6 BlackPill board from WeAct..
252145709-9615b9e7-84cc-44e3-9a02-99425d882490
I also reduced the pull-up resistors from 10 kΩ to 4.7 kΩ.
Looking ahead, I will say that this did not change anything in the work.
About I2C connection here.
Core for Arduino IDE here.
Bought two bread-boards MPU9250 and began to look for libraries to work with accelerometers, gyroscopes and magnetometers.
I tried the bolderflight library, but it constantly gave an error connecting to the serial port.

PS C:\Users\Admin> arduino-cli monitor -p COM6 -c baudrate=115200
Monitor port settings:
baudrate=115200
Connected to COM6! Press CTRL-C to exit.
Error initializing communication with IMU

252349472-36a15c5f-d3fc-4292-a03c-c7f974d8ce19
Also tried the asukiaaa library, but there is also a problem with the connection.
In order to deal with the problem, I connected using the I2C bus analyzer and saw that the sensor gives a response of 0x70 to the "who-I-am" request.
252349151-2f6803a4-18d3-4ecb-9eee-02c19313a652

From this, I realized that my boards are fake, and there is no magnetometer on them.
I was very frustrated that I could not try and use the MPU9250 boards for my navigation tasks - I wrote an angry letter to the seller from Aliexpress, but he did not even answer me ...
What was my surprise when, having loaded the sketch of the SparkFan library, I saw the treasured readings of the accelerometer and gyroscope.

Accel: -0.01, 0.09, 1.01 g
Gyro: -4.57, 4.51, 1.65 dps
Mag: 0.00, 0.00, 0.00 uT
Time: 118769 ms

Accel: -0.02, 0.12, 1.01 g
Gyro: -4.70, 2.99, 2.01 dps
Mag: 0.00, 0.00, 0.00 uT
Time: 120776 ms

Accel: -0.02, 0.14, 1.01 g
Gyro: -4.45, 3.54, 2.01 dps
Mag: 0.00, 0.00, 0.00 uT
Time: 122785 ms

Accel: -0.04, 0.17, 1.00 g
Gyro: -4.76, 2.99, 2.01 dps
Mag: 0.00, 0.00, 0.00 uT
Time: 124796 ms

The magnetometer of course showed zeros.
252167195-e587a91c-4687-4fdf-b793-d44e798876fe
I also tried uploading a sketch with a quaternion calculation, and it also worked, although I thought that to calculate the quaternion - you need data from a magnetometer.

I fiddled with countless firmware and library downloads for about three days.
The next day, I demanded to upload the SparkFan sketch again to my stm32f401ccu6 board, and to my extravagance, the serial port did not give out any data.
I decided to check the communication on the I2C bus - also silence.
I thought maybe something happened to his PC overnight and rebooted.
After the reboot, I got a BSOD and spent another three days trying to restore the work of a personal computer - the SSD broke (and I think this happened because of its 4-year work).

While I was restoring the PC, I tried to download the SparkFan sketch on my second computer (laptop), but it still did not work.
I have already begun to think that perhaps it seemed to me that the MPU9250 board worked and gave out data, but the screenshots do not let me forget this.
252343495-0610fea0-949a-4ca4-95e9-1b9b227c5ab5
Now I'm working on a restored PC, but none of the libraries for the MPU9250 work.
I don’t know what it was .... a miracle or what happened to the hardware (my STM32 microcontroller, MPU9250 board, STmicroelectronics core for Arduino or some other mysticism.)
Can anyone give some advice/information on what happened?
Commands are sent via the I2C bus from the microcontroller to the MPU9250, but there is no output to the serial port, as if the controller freezes.
But I have already changed three microcontrollers, I also tried to run the code on the ESP32 ... the same thing.
I remembered what I did before the SSD crashed, and it seems like I updated the core, but the branch itself does not consider that the problem is with the core and I2C.

dmpSetAccelBias is undefined

Hi,
I'm trying to read RPY values but they are floating all the time.
Is there any way to load calibrated values?

It seems there is a method: MPU9250_DMP::dmpSetAccelBias(long*) but there is no implementation.

Please provide a calibration example so that RPY values don't change when the IMU is standing still.

Thanks in advance!

Strange reset behaviour

It works as intended after the first sketch upload. After that if I unplug usb cable thus cutting the both devices power and plug back - the fun starts here) The sketch is working, but this time the response from mpu9250 is like 10 times slower. Here is the weird part - it still works, but just shows the data slower in Serial Monitor and the led blinks slower.

What am I doing wrong? Thanks.

How to get absolute yaw with DMP

Hi i tried using MPU9250_DMP_Quaternion sketch and get good value with yaw, but i have a little problem how to do make yaw relative earth north, i observe roll and pitch is fix when initialization on any attitude, but yaw is not fix.

Esp32 Serial1 not working with this Library

I'm using the ESP32 and if I use a different Library for the MPU9250 such as the one from BolderFlight then it works flawlessly. But when I use the sparkfun DMP Library with the DMP then it too works fine except for the serial1 where I have a SBUS receiver hooked up. It looks as if when the first bytes are recieved it works but after the first complete set of data I don't get anymore readings from the serial1. Everything else keeps working except for Serial1. And as I said other libraries do work with Serial1.
Also the Mpu9250 is connected over I2C.

linear acceleration values

Is it possible to get linear acceleration values free of gravity from the DMP on the mpu9250? I see a calculation on
float accelX = imu.calcAccel(imu.ax);

however Im not sure if accelX is the linear acceleration.

Use 2 IMU with 1 arduino

Hi !

I'm working on a project that needs 2 IMUs in order to locate 2 hardware pieces relatively to each other.

Is it possible to use 2 IMUs on a single MKRZERO ?

Thanks

Bug38

Using DMP and Wake on Motion

Hi everyone,

I'd like to be able to use the DMP function of the MPU9250 with Wake On Motion (WOM).
I want the MPU to maintain it pose calculation (using DMP) when the microcontroller is in sleep mode.
I then want the MPU to wake the microcontroller on an acceleration trigger.

Is there any way to do this with this library? I have seen WOM implemented with the bolder-flight library:
https://github.com/bolderflight/MPU9250

Any help is appreciated,
Nick

Bricked 3 mkr zero boards with this card - advice please!! :(

I am trying to get the 9250 working but am falling at the first hurdle. I am trying to run the code at the hookup guide tutorial, but after it compiles and runs my mkrzero is then bricked. By board three I was super careful - checking resistance between vcc/gnd on the 9250 to check for shorts and I could hook up the board to the mkr zero vcc,gnd, scl and sda and run 'blink' and all is fine - nothing blows yet. BUT as soon as I run the example code, that's it - nothing.
Any advice very gratefully received!!

Magnetormeter Data seems not right

When i collect magnetor data MAX and MIN to calculate magnetor offset
I have turned sensor crazy in the air but at the end, this is what i got

magn x,y,z (min/max) = -156.04/636.16 -600.15/268.57 -694.67/157.54

Quaternion DMP calulation not working on Mega 2560

I ran MPU9250_DMP_Quaternion.ino without any problem on an ESP8266.
Now I want to use it on a Arduino Mega 2560 and it returns the following:

Q:    INF,    INF,    INF,    INF
R/P/Y:  NAN, 180.00,  NAN
Time: 32761 ms

MPU9250_DMP_Gyro_Cal.ino works correctly on the same Arduino Mega 2560.

I tried DMP_FEATURE_6X_LP_QUAT and DMP_FEATURE_LP_QUAT both gives the same.

Also, dmpBegin returns INV_SUCCESS.

I also tried with Wire.setClock(400000), no success...

Any idea what could cause this issue?

SPI support?

SPI support would be great for a) higher data rates, and b) support more than a few devices without having to use the i2c AD0 pull up/down trick (which for me wasn't working with the MPU-9250).

Bug in setLowPass Filter Function - Accel lowpass is never configured

The function "imu.setLPF();" does not set the Accel Low Pass register but only the Gyro and Temperature Lowpass. i thing that is due to the difference to the very similar MPU6050 where both accel and gyro LP are set in the same register.

Hier the incorrect function call from the Example Library


// setLPF() can be used to set the digital low-pass filter
// of the accelerometer and gyroscope. (<- This is Wrong)
// Can be any of the following: 188, 98, 42, 20, 10, 5
// (values are in Hz).
imu.setLPF(42); // Set LPF corner frequency to 5Hz


The correct way to set the Accel Low Pass is to write to the MPU9250_ACCEL_CONFIG_2 register.
1.) Disable Bypass by setting the bypass bit to 0 (it is inverted from the given table in the datasheet
2.) Set lowpass config bits to the desired value.

here is an example code:


void MPU9250Class::setAccelLowPass(int f_cutoff)
{

#define REG_MASK_ACCEL_LP 0b1111
#define REG_VAL_ACCEL_LP_218Hz 0
#define REG_VAL_ACCEL_LP_99Hz 2
#define REG_VAL_ACCEL_LP_44Hz 3
#define REG_VAL_ACCEL_LP_21Hz 4
#define REG_VAL_ACCEL_LP_10Hz 5
#define REG_VAL_ACCEL_LP_5Hz 6

	uint8_t data = 0;
	if (f_cutoff >= 218)
		data = REG_VAL_ACCEL_LP_218Hz;
	else if (f_cutoff >= 99)
		data = REG_VAL_ACCEL_LP_99Hz;
	else if (f_cutoff >= 44)
		data = REG_VAL_ACCEL_LP_44Hz;
	else if (f_cutoff >= 21)
		data = REG_VAL_ACCEL_LP_21Hz;
	else if (f_cutoff >= 10)
		data = REG_VAL_ACCEL_LP_10Hz;
	else
		data = REG_VAL_ACCEL_LP_5Hz;

	imu.write_mask(mpu9250_register::MPU9250_ACCEL_CONFIG_2, REG_MASK_ACCEL_LP, data);

}

The write_mask function is one I have added to make the i2c function accessible from the outside to implement further functions but the logic should be clear.

It should also me noted that setLPF should be called after setting the sample rate because setting the samplerate changes the LPF to half the sample frequency.
That is also a bug in the basic example:

  // setLPF() can be used to set the digital low-pass filter
  // of the accelerometer and gyroscope.
  // Can be any of the following: 188, 98, 42, 20, 10, 5
  // (values are in Hz).
  imu.setLPF(5); // Set LPF corner frequency to 5Hz

  // The sample rate of the accel/gyro can be set using
  // setSampleRate. Acceptable values range from 4Hz to 1kHz
  imu.setSampleRate(10); // Set sample rate to 10Hz

No Wire.endTransmission() needed after Wire.requestFrom()

In the file "util/arduino_mpu9250_i2c.cpp" in the function "arduino_i2c_read()", there is a Wire.endTransmission() after the Wire.requestFrom(). The Wire.endTransmission() should only be used when writing data, since the Wire.requestFrom() is a complete I2C session on its own.

The unnecessary extra Wire.endTransmission() causes an extra I2C transaction for the AVR chips (I don't know about other Wire libraries). The Master sets the I2C address on the bus, and the MPU-9250 acknowledges that. That makes it slower.

Change I2C address

Excuse me.
Is it possible to read quaternion data from two MPU9250 sensors?

qToFloat mask uninitialized

see lines 613-621 of src/SparkFunMPU9250-DMP.cpp

in MPU9250_DMP::qToFloat(), mask is not initialized to 0, and thus the top 32-q bits may be set to 1 undesirably

Reboot in SparkFunMPU9250-DMP.cpp at line 46

Hello,

I use
#include <U8g2lib.h>
#include <Arduino.h>
#include <SPI.h>
#include <SparkFunMPU9250-DMP.h>
#include <Chrono.h>
#include "OneButton.h"

if I run screen u2g2lib, chrono, onebutton in first : no problem
After ESP8266 wemos D1 mini reboot with
result = mpu_init(&int_param); in SparkFunMPU9250-DMP.cpp

what is the solution please ?

SparkFunMPU9250-DMP.cpp

Unsufficient I2C baud-rate

The baud-rate between the MPU9250 and the microcontroller is not specified explicitly. When trying to sample the DMP at 200 Hz, this caused some drops in the gyroscope readings, which in turn also affected the angle computation. And therefore my balancing controller was unstable
Adding the line:
Wire.setClock(400000); after Wire.begin();
in the inv_error_t MPU9250_DMP::begin(void) function resolved all issues.

endless loop with vibration

I'm currently building an arduino drone and I have the problem, that the IMU code gets stuck somewhere if the Propeller speed is at a certain rate. This only happens, if the IMU is sticked to the drone. If I take the IMU of the drone and hold it in my hands, there is no error and everything runs fine.

Dos anyone have an idea why this could happen? Is it possible that the IMU gets stuck, when it experiences to much vibration?

The soldering of the IMU should be fine. There is no problem, if you touch / bend the cable.

Euler calculation improvements

SparkFunMPU9250-DMP.cpp line #641 seems to have an error: The multiplication with 2 is superflous.
Apart from that, the Euler angle calculation results in "strange" angles. See discussion here:
https://forum.sparkfun.com/viewtopic.php?f=14&t=45516
With the following code I get expected results:

`static void toEulerianAngle(float w, float x, float y, float z, double& roll, double& pitch, double& yaw)
{
double ysqr = y * y;

// roll (x-axis rotation)
double t0 = +2.0 * (w * x + y * z);
double t1 = +1.0 - 2.0 * (x * x + ysqr);
roll = atan2(t0, t1);

// pitch (y-axis rotation)
double t2 = +2.0 * (w * y - z * x);
t2 = t2 > 1.0 ? 1.0 : t2;
t2 = t2 < -1.0 ? -1.0 : t2;
pitch = asin(t2);

// yaw (z-axis rotation)
double t3 = +2.0 * (w * z + x * y);
double t4 = +1.0 - 2.0 * (ysqr + z * z);
yaw = atan2(t3, t4);
}
`
This is based on code from here:
https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles

~60 MS DELAY EVERY ~.5S

The IMU will have these random delays/gaps every so often where it doesn't transmit for around 60ms every .5 seconds or so: This is a zoomed in picture of an Euler angle output vs the time log:

image

All I am doing is checking fifoAvailable, then doing dmpUpdateFifo. There are no delays or loops in my code. The dmpbegin is initialized with a fifo rate of 200 Hz,

Timing

Hi and thank you for this very handy library!

I'm currently getting into the basic example and I noticed that the timestamp (imu.time) it prints out isn't quite consistent. Despite a sample rate (imu.setSampleRate) of 10Hz the timestamp indicates a sample interval of 99ms instead of 100ms every 6 or 7 samples.

Is there a way to get very accurate measurements timewise? So that even if there's a delay in one update, the next will be in time again?

Thank you,

Regards
Dom

Which coordinate system does the DMP quaternion for the MPU-9250 initalise in?

When I use your library to fetch the DMP quaternion, I get different values in different initialising orientations. So, I was wondering which coordinate system the DMP quaternion for the MPU-9250 initalise in? Was thinking that it might just initialise with respect to a gravity vector. Could you confirm whether this is the case/provide any insight?

Calibrate gyro and accel offsets?

Hello!

I am trying to put a MPU9250 in a car to use for YPR calculations. Since the vehicle and therefore MPU9250 won't always start on a perfectly flat plane I need to apply offsets to the output data.

Is there a easy way to do this using the registers in the MPU9250, or would it be easier to just offset the final calculations?

Problem with magnetometer

I can read the gyroscope and the accelerometer, but not the magnetometer, the values of mx, my, and mz are always zero.

Unable to Read Compass in FiFO mode due to bug

There is a bug in the Code in case you want to read Accel and/or Gyro in fifo mode and also read the Compass Data.
The problem is caused because of the internal variable st.chip_cfg.bypass_mode (in inv_mpu.c) is per default True. In Regular Setup (without using FIFO) the Aux I2C is used in Master Mode (bypass disabled). The bypass flag is not used and the register is written directly to.
When switching to FIFO mode with configuring FIFO the st.chip_cfg.bypass_mode flag is used to determine the I2C_MST_EN bit in USER CONTROL register.

That means the AUX I2C port switches to bypass when configuring fifo.

Here the setup that causes the bug:

imu.setSensors(INV_XYZ_GYRO | INV_XYZ_ACCEL | INV_XYZ_COMPASS);
imu.setGyroFSR(2000); // Set gyro to 2000 dps
imu.setAccelFSR(2); // Set accel to +/-2g
imu.setLPF(5); // Set LPF corner frequency to 5Hz
imu.setSampleRate(AG_SAMPLE_RATE); // Set sample rate to 10Hz
//MPU9250_USER_CTRL: **00100000**
**imu.configureFifo(INV_XYZ_GYRO | INV_XYZ_ACCEL);**
//MPU9250_USER_CTRL: **01000000**


Solution: Set the st.chip_cfg.bypass_mode flag to false while initializing:
(note: AK89xx_SECONDARY is defined. AK89xx_BYPASS is not defined


int mpu_set_sensors(unsigned char sensors)
{
   [...]
    if (sensors && (sensors != INV_XYZ_ACCEL))
        /* Latched interrupts only used in LP accel mode. */
        mpu_set_int_latched(0);

#ifdef AK89xx_SECONDARY
#ifdef AK89xx_BYPASS
    if (sensors & INV_XYZ_COMPASS)
        mpu_set_bypass(1);
    else
        mpu_set_bypass(0);
#else
	**st.chip_cfg.bypass_mode = 0;**
    if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &user_ctrl))
        return -1;
    /* Handle AKM power management. */
    if (sensors & INV_XYZ_COMPASS) {
        data = AKM_SINGLE_MEASUREMENT;
        user_ctrl |= BIT_AUX_IF_EN;
    } else {
        data = AKM_POWER_DOWN;
        user_ctrl &= ~BIT_AUX_IF_EN;
    }
[...]

}

This might not the best fix but it solves my problem. I'm sure there is a better solution.

Mag Calibration Missing

Hello,
Is a great Libary but I missing mag calibration. Why never be implemented ?
So the compass never could be work corect.
regards

Arduino: SerialUSB not declared in scope

MPU9250_Basic:20: error: 'SerialUSB' was not declared in this scope

#define SerialPort SerialUSB

                ^

C:\Users\Jonathan\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\examples\MPU9250_Basic\MPU9250_Basic.ino:26:3: note: in expansion of macro 'SerialPort'

SerialPort.begin(115200);

^

C:\Users\Jonathan\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\examples\MPU9250_Basic\MPU9250_Basic.ino: In function 'void printIMUData()':

MPU9250_Basic:20: error: 'SerialUSB' was not declared in this scope

#define SerialPort SerialUSB

                ^

C:\Users\Jonathan\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\examples\MPU9250_Basic\MPU9250_Basic.ino:113:3: note: in expansion of macro 'SerialPort'

SerialPort.println("Accel: " + String(accelX) + ", " +

^

exit status 1
'SerialUSB' was not declared in this scope

Custom Sercom Ports

Hello!
I've been trying to change standard Wire to the custom pins 3 and 4.
I tried my best which is definitely not enough. I've done it with other sensors, they worked fine. It's just me not being able to put the code in the right place.
Can you give any advice on that, please?

Here's the code I'm trying out:

#include <Wire.h>
#include "wiring_private.h" // pinPeripheral() function
TwoWire IMUWire(&sercom2, 4, 3);
    // Assign pins 4 & 3 to SERCOM functionality
    pinPeripheral(4, PIO_SERCOM_ALT);
    pinPeripheral(3, PIO_SERCOM_ALT);
    IMUWire.begin();

P.S. I tried the beginning of .begin() func in ...MPU9250-DMP.cpp, inv_mpu.c and arduino_mpu9250_i2c.c

Thank you!
Dmitry

Quaternions are out of range -1 to 1

Output quaternions q1, q2, q3 in MPU9250_DMP_Quaternion.ino are in range from -1 to 2. Should be from -1 to 1. Also I noticed pitch angle is not calculated properly - rotating device by 45 deg shows 90 deg pitch angle rotation.

Doesn't work on Arduino Uno

Hi thanks for the great work. But I found the sketch too large for my Arduino Uno R3 and the memory required is 188% which results in an error.
Is there any MPU 9250 DMP library that works for Uno?

Many thanks!

Mpu9250 does not work with ESP32 1.0.0 release (latest)

I have the https://www.sparkfun.com/products/13762 9250 i2c breakout board. When I got this it seemed to be running fine but with the latest release of ESP32 arduino support this doesn't seem to work any more.

All the samples such as MPU9250 basic appear to startup and are trying to read the 9250 but no data is ever returned. Checking this on a Saleae logic analyzer shows that all the writes to the 9250 are ACKed but all the reads are NAKed.

I have tried adding 3.3k pullups to the setup, but this does not make any difference.
I have tried using 100,000 and 400,000 speeds on Wire, no difference.

I have also double-checked the wires, only 4 (2 power and SDA/SCL, and they are correct.

On one of my computers at home these samples DO seem to work, but I think that machine might have an older release of the ESP32 arduino libraries, I will check that and report back soon.

If it would be helpful, I can post a dump of the I2C traffic from my logic analyzer (software to view it is free). If anyone wants it, let me know, I need to re-capture the data to shrink it's size a bit.

[Arduino IDE] Error Compiling for Raspberry Pi Pico

I tried to compile the "Quaternion" example for RPi Pico from Arduino IDE using the "Arduino MBED OS for RP2040 Boards" Board Library by Arduino itself.
But I get the following error when Compiling:

"""
WARNING: library SparkFun_MPU-9250-DMP_Arduino_Library-master claims to run on samd architecture(s) and may be incompatible with your current board which runs on mbed_rp2040 architecture(s).
In file included from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\variants\RASPBERRY_PI_PICO/pinmode_arduino.h:30:0,
from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/Arduino.h:26,
from C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\arduino_mpu9250_clk.c:19:
C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/api/Common.h:76:9: error: unknown type name 'bool'
typedef bool boolean;
^~~~
In file included from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\variants\RASPBERRY_PI_PICO/pinmode_arduino.h:30:0,
from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/Arduino.h:26,
from C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu_dmp_motion_driver.c:35:
C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/api/Common.h:76:9: error: unknown type name 'bool'
typedef bool boolean;
^~~~
In file included from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\variants\RASPBERRY_PI_PICO/pinmode_arduino.h:30:0,
from C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/Arduino.h:26,
from C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c:39:
C:\Users\athar\AppData\Local\Arduino15\packages\arduino\hardware\mbed_rp2040\3.1.1\cores\arduino/api/Common.h:76:9: error: unknown type name 'bool'
typedef bool boolean;
^~~~
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c: In function 'reg_int_cb':
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c:52:1: warning: no return statement in function returning non-void [-Wreturn-type]
}
^
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu_dmp_motion_driver.c: In function 'dmp_set_accel_bias':
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu_dmp_motion_driver.c:605:5: warning: implicit declaration of function '__no_operation'; did you mean '__section'? [-Wimplicit-function-declaration]
__no_operation();
^~~~~~~~~~~~~~
__section
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c: In function 'mpu_reg_dump':
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c:47:19: warning: implicit declaration of function '_MLPrintLog' [-Wimplicit-function-declaration]
#define log_i _MLPrintLog
^
C:\Users\athar\Documents\Arduino\libraries\SparkFun_MPU-9250-DMP_Arduino_Library-master\src\util\inv_mpu.c:612:9: note: in expansion of macro 'log_i'
log_i("%#5x: %#5x\r\n", ii, data);
^~~~~
exit status 1
Error compiling for board Raspberry Pi Pico.
"""

How can I get around this error?

MPU on raspberry pi 4

hi!
thanks Gods i have implemented MPU on raspberry pi 4 raspbian with ROS noetic and
everything works perfects with vpython example.
i plan to use MPU with ORB_SLAM3.

here`s my steps if someone want to follow:

*http://wiki.ros.org/razor_imu_9dof
pip3 install --upgrade pip
pip3 install cryptography==3.4.6
pip3 install vpython

cd catkin_ws/src
git clone https://github.com/ENSTABretagneRobotics/razor_imu_9dof.git
source /home/pi/catkin_ws/devel/setup.bash
cd .. &&  catkin_make
cd src/razor_imu_9dof/nodes
wget https://www.glowscript.org/docs/VPythonDocs/VPtoGS.py ; python3 VPtoGS.py ; cp -f Converted/display_3D_visualization.py display_3D_visualization.py ; cd ../../..
roscd razor_imu_9dof/config
cp razor.yaml my_razor.yaml
*find MPU on USB ports:
dmesg | grep tty

*https://learn.sparkfun.com/tutorials/9dof-razor-imu-m0-hookup-guide/all
install arduino ide 1.8.18
put to preferences:
	https://raw.githubusercontent.com/sparkfun/Arduino_Boards/master/IDE_Board_Manager/package_sparkfun_index.json

Board Manager -> SparkFun SAMD Boards-> install
roscd razor_imu_9dof
cp -r src/Razor_AHRS ~/Arduino
select SparkFun 9DoF Razor IMU M0 to upload
uncomment in Razor_AHRS.ino:
	#define HW__VERSION_CODE 14001 // SparkFun "9DoF Razor IMU M0" version "SEN-14001"
upload Razor_AHRS.ino

test:
roslaunch razor_imu_9dof razor-pub-and-display.launch
or 
roslaunch razor_imu_9dof razor-pub.launch

But i have some questions:
1.
how to set frequency of MPU ?
i have change my_razor.yaml:
pub_rate: 200.0
is that the way?
2.
how to understand axis on the board ?
i saw X and Y arrows of MAG and GYRO. they are in different directions. and what about Z ? crossed cirlce means FACE UP or DOWN ?

could you help a bit ?

dmp_set_fifo_rate() dependent on SMPLRT_DIV

Note that this concerns a src/util file, and therefore may be out of the scope of Sparkfun contributions.

in dmp_set_fifo_rate() (line 648 of src/util/inv_mpu_dmp_motion_driver.c), I had to change the function to reflect that the DMP FIFO rate appeared to be 4x larger than what I expected it to be:

div hz_expected hz_actual
0 200 800
1 100 400
3 50 200
4 40 160
7 25 100
15 12.5 50

Other relevant configuration is that gyro was set to 1kHz (DLPF_CFG to 0x01) since I read in the datasheet that DMP would not function if there was an 8kHz sampling rate, which is default for gyro. Note that accel sampling rate is 1kHz by default.

However, when I set the SMPLRT_DIV to 0x04 (i.e. 1kHz/(4+1) = 200Hz), I get frequencies that I would expect based on the existing code.

And finally, when I set the SMPLRT_DIV to 0x09 (i.e. 1kHz/(9+1) = 100Hz), I get frequencies that are 2x small than expected.

My point is that the DMP FIFO rate appears dependent on SMPLRT_DIV. That relationship seems to be that the DMP FIFO further subdivides SMPLRT_DIV, but maxes out at 800Hz. Therefore, dmp_set_fifo_rate() assumes SMPLRT_DIV = 0x04 s.t. 1kHz/(4+1) = 200Hz.

Using two MPU9250s at the same time

Has anyone managed to use this library (with modification) to support using more than one 9250 at a time?

I've made some basic changes to pass the I2C address through in the begin function, however it gets overwritten by subsequent calls from a different object instance.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.