kriswiner / MPU9250

Arduino sketches for MPU9250 9DoF with AHRS sensor fusion
1.03k stars 471 forks source link

Very stable pitch but noisy yaw and roll #344

Open masrim2000 opened 5 years ago

masrim2000 commented 5 years ago

Hi everyone. First of all, thank you kriswiner for your effort and great work. I'm using an MPU9250 with an STM32F103 (blue pill) which has a 72MHz clock speed. After calibrating the mag I recorded and plotted this data: mag_cal

The problem I'm having is that the pitch angle is very nice and smooth, but the yaw and roll angles have much more noise: ahrs (Blue=Yaw, Red=Pitch, Green=Roll)

The noise pattern seems to be identical but inverted and scaled up on yaw, which seems strange.

Is this normal? Should the Red line be like the other two or should the other two be more like the Red one?

This is the order I'm feeding the values into the fusion filter: MahonyQuaternionUpdate(-ax, ay, az, gx, -gy, -gz, my, -mx, mz) (+Ax points to north and I had to multiply A values by -1 to get it to work properly)

this is the output from the Serial monitor on startup: MPU9250 I AM 0x71 I should be 0x71 MPU9250 is online... x-axis self test: acceleration trim within : 1.8% of factory value y-axis self test: acceleration trim within : -1.1% of factory value z-axis self test: acceleration trim within : 2.1% of factory value x-axis self test: gyration trim within : -3.6% of factory value y-axis self test: gyration trim within : -0.5% of factory value z-axis self test: gyration trim within : 0.2% of factory value MPU9250 initialized for active data mode.... AK8963 I AM 0x48 I should be 0x48 AK8963 initialized for active data mode.... X-Axis factory sensitivity adjustment value 1.19 Y-Axis factory sensitivity adjustment value 1.20 Z-Axis factory sensitivity adjustment value 1.15 AK8963 mag biases (mG) 359.06 676.08 858.72 AK8963 mag scale (mG) 0.98 1.03 0.99 Magnetometer: X-Axis sensitivity adjustment value 1.19 Y-Axis sensitivity adjustment value 1.20 Z-Axis sensitivity adjustment value 1.15

kriswiner commented 5 years ago

Looks like you are doing everything about right.

The F103 is likely not going to give you the fusion rate you need for best results. What is the fusion rate now? I would guess ~500 Hz...

You could try higher data sample rates if your MCU can support that. I have had good results running at accel/gyro rates of 200 Hz, mag rate of 100 Hz and then fusion rates well above 1 kHz (the higher the better).

Even lower jitter can be had at 1 kHz accel/gyro rates, but then the MCU needs to be able to manage fusion at 4 - 5 kHz.

It looks like one or more of your 9 sensor outputs is displaying a lot of jitter, likely a magnetometer axis. I would take a look at the sensor data and plot the nine values as a function of time to see where the jitter lies. It is possible you don't have the sensor configuration set properly...maybe the bandwidth (low frequency filter) is not set properly, or ?

On Sun, Feb 3, 2019 at 9:40 PM masrim2000 notifications@github.com wrote:

Hi everyone. First of all, thank you kriswiner for your effort and great work. I'm using an MPU9250 with an STM32F103 (blue pill) which has a 72MHz clock speed. After calibrating the mag I recorded and plotted this data: [image: mag_cal] https://user-images.githubusercontent.com/47311599/52191309-1e77a700-2855-11e9-950d-b0f3f598ab2f.jpg

The problem I'm having is that the pitch angle is very nice and smooth, but the yaw and roll angles have much more noise: [image: ahrs] https://user-images.githubusercontent.com/47311599/52191686-0bfe6d00-2857-11e9-82bb-098d07d249bf.JPG (Blue=Yaw, Red=Pitch, Green=Roll)

The noise pattern seems to be identical but inverted and scaled up on yaw, which seems strange.

Is this normal? Should the Red line be like the other two or should the other two be more like the Red one?

This is the order I'm feeding the values into the fusion filter: MahonyQuaternionUpdate(-ax, ay, az, gx, -gy, -gz, my, -mx, mz) (+Ax points to north and I had to multiply A values by -1 to get it to work properly)

this is the output from the Serial monitor on startup: MPU9250 I AM 0x71 I should be 0x71 MPU9250 is online... x-axis self test: acceleration trim within : 1.8% of factory value y-axis self test: acceleration trim within : -1.1% of factory value z-axis self test: acceleration trim within : 2.1% of factory value x-axis self test: gyration trim within : -3.6% of factory value y-axis self test: gyration trim within : -0.5% of factory value z-axis self test: gyration trim within : 0.2% of factory value MPU9250 initialized for active data mode.... AK8963 I AM 0x48 I should be 0x48 AK8963 initialized for active data mode.... X-Axis factory sensitivity adjustment value 1.19 Y-Axis factory sensitivity adjustment value 1.20 Z-Axis factory sensitivity adjustment value 1.15 AK8963 mag biases (mG) 359.06 676.08 858.72 AK8963 mag scale (mG) 0.98 1.03 0.99 Magnetometer: X-Axis sensitivity adjustment value 1.19 Y-Axis sensitivity adjustment value 1.20 Z-Axis sensitivity adjustment value 1.15

β€” You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qmPjl6TeLm0wNYX75-Mlo9FKvx6dks5vJ8fegaJpZM4aglEH .

masrim2000 commented 5 years ago

Thanks for the quick reply.

The fusion rate normally is around 2.5 kHz. And almost exactly 2 kHz if I force 10 quaternion updates after each data read, using a for loop.

I'm running accel/gyro at 200 Hz and mag rate 100 Hz. (sorry I didn't mention it earlier, hate making you repeat yourself all the time)

I tried plotting all the sensor outputs to see if any of them had anything suspecious: sensor output data

I think they all look fine. What do you think?

The accel and gyro LPF bandwidth is set to 41 Hz just like you use in your sketches. I also tried reducing it to 5 Hz but the response plot is pretty much the same (when the device is at rest).

Any idea what other sensor configuration parameters could be responsible?

edit: a better plot showing the 9 sensors output: sensor output data2

kriswiner commented 5 years ago

Looks like you know what you are doing (rare to have such a customer!). The data look OK except the mag jitter is really quite large, I make it almost ten percent in Mz, more for the others. I think this is the problem. This jitter will feed right into the yaw. You could try another MPU9250 to see if it is just a "bad" sensor or you have a lot of noise in your environment/system...Otherwise the setup and configuration look right and you should be able to get stable heading to ~4 degrees rms absolute accuracy or better. Typical heading jitter should be much less, maybe 1 degree or lower...

masrim2000 commented 5 years ago

Thank you kriswiner, I'll get another sensor and see if it makes a difference. Btw, I calculated the Mz jitter percentage, and wow its 10.6 percent!! Can't believe you eyeballed it with such accuracy from these plots πŸ‘

kriswiner commented 5 years ago

Yeah, this is likely the problem. it is not normal...

On Mon, Feb 4, 2019 at 5:05 PM masrim2000 notifications@github.com wrote:

Thank you kriswiner, I'll get another sensor and see if it makes a difference. Btw, I calculated the Mz jitter percentage, and wow its 10.6 percent!! Can't believe you eyeballed it with such accuracy from these plots πŸ‘

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-460475688, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qn0ytGdkai8SI9YDBPStK5JRW4wBks5vKNjkgaJpZM4aglEH .

masrim2000 commented 5 years ago

After trying many different breakout boards (multiple cheap gy-9250 blue boards and a couple of Sparkfun's) and countless attempts, I still can't figure it out. The problem seems to be caused by the large mag jitter, but all the boards I tried are giving me similar mag readings. I tried going outside to an open field in case the room I was working in is magnetically noisy, but I didn't notice any improvement.

I tried to isolate the cause of the problem by:

I'm not sure what else I can try. Is it possible that all the sensors I tried are "bad"? Or that the entire area I live in has this magnetic noise?

It's really strange that no one else seems to have posted anything similar to my issue.

Any suggestions will be appreciated.

masrim2000 commented 5 years ago

I tried to just live with it and use a filter for the mag readings. But even then it was bad, I couldn't find a sweet spot where there is adequate filtering and low latency.

kriswiner commented 5 years ago

Last thing I can recommend is to try a different sensor suite, like this https://www.tindie.com/products/onehorse/all-st-motion-sensor-breakout-board/ one.

On Thu, Feb 14, 2019 at 12:11 PM masrim2000 notifications@github.com wrote:

I tried to just live with it and use a filter for the mag readings. But even then it was bad, I couldn't find a sweet spot where there is adequate filtering and low latency.

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-463775693, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qmopCbZsMbY6Ml8zOOdqoSl9UkUnks5vNcMDgaJpZM4aglEH .

masrim2000 commented 5 years ago

Will do. I also ordered one of your MPU9250 just to check if the issue is related to the boards I was using. Many thanks.

kriswiner commented 5 years ago

So despite (or because of) the large mag jitter you aren;t getting stable yaw, right? I mean what is the percentage of yaw jitter you are seeing again, also ~10%?

On Thu, Feb 14, 2019 at 2:34 PM masrim2000 notifications@github.com wrote:

Will do. I also ordered one of your MPU9250 just to check if the issue is related to the boards I was using. Many thanks.

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-463829816, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qhTdscyraD09P3S0MXUJIZeXIwhpks5vNeRigaJpZM4aglEH .

masrim2000 commented 5 years ago

Yes, almost 2 degrees yaw jitter (approximately from -1 to +1 when at 0)

kriswiner commented 5 years ago

That's at least 2x more than it should be.

When I run with a fast MCU (STM32L4, for example) I usually see < 1 degree yaw jitter. It varies with the sensor and depends on how well calibrated I am. Somthing liek this is typical (ST sensors):

02/11/19 08:53:25.891,*-50.4,-30.3,1002.7 ,-0.1,-0.1,-0.1,-9.5,15.3,-49.5,158.46,-1.80,2.76,-49.8,-81.8,1001.4,-0.0,0.1,0.1,-13.7,4.1,-48.5,352.36,-52.60,109.46 02/11/19 08:53:26.295,-50.8,-31.3,1002.5,0.2,0.0,0.1 ,-9.3,15.0,-48.8,158.76,-1.76,2.82,-51.5,-81.9,1000.7,-0.1,0.2,0.1,-14.0,4.2,-49.1,12.20,-55.86,91.92 02/11/19 08:53:26.698,-50.0,-30.5,1003.6,-0.3,0.0,-0.0,-9.2,15.0,-49.5 ,158.52,-1.72,2.82,-50.9,-82.7,999.3,-0.1,0.0,0.0,-13.7,4.2,-49.1,37.90,-54.84,68.94 02/11/19 08:53:27.102,-50.6,-30.3,1002.3,0.0,0.0,-0.0,-8.9,15.2,-48.0, 158.52,-1.68,2.90* ,-49.8,-82.3,1001.2,0.0,-0.1,0.0,-13.5,4.5,-49.1,63.10,-47.02,46.62 02/11/19 08:53:27.506,-49.7,-30.0,1002.7,-0.1,0.1,0.0,-9.3,14.9,-49.1,158.26,-1.80,2.70,-50.3,-82.3,999.9,-0.0,-0.2,-0.0,-14.4,4.4,-48.3,82.40,-32.24,29.52 02/11/19 08:53:27.911,-50.0,-30.3,1002.5,0.1,0.0,0.1,-9.2,15.0,-48.5,158.62,-1.68,2.86,-49.8,-80.8,1000.2,-0.1,-0.2,-0.1,-13.2,4.7,-48.5,95.78,-12.20,15.16 02/11/19 08:53:28.316,-50.1,-30.7,1003.9,-0.2,0.0,-0.1,-8.7,15.5,-49.2,158.62,-1.66,2.90,-49.8,-81.2,1000.2,-0.1,0.1,0.1,-14.0,3.8,-48.8,113.50,-2.92,3.36 02/11/19 08:53:28.718,-48.9,-30.1,1002.8,-0.1,0.0,0.0,-9.6,15.5,-49.2,158.28,-1.74,2.80,-49.9,-82.0,999.5,0.1,0.0,0.1,-13.8,4.1,-48.9,129.74,-4.70,2.84 02/11/19 08:53:29.119,-49.9,-30.6,1003.4,-0.4,0.1,-0.1,-9.2,14.7,-48.9,158.66,-1.80,2.72,-49.8,-81.4,1001.4,0.2,-0.1,-0.1,-13.8,4.2,-48.5,129.92,-4.64,2.82 02/11/19 08:53:29.519,-49.7,-29.3,1002.5,-0.1,0.0,0.0,-9.3,15.2,-48.6,158.46,-1.76,2.78,-50.8,-81.3,1001.1,0.1,-0.2,0.1,-13.7,4.7,-48.0,129.98,-4.52,2.96 02/11/19 08:53:29.923,-49.6,-28.7,1003.1,-0.2,0.1,-0.0,-8.6,15.2,-48.3,158.96,-1.64,2.88,-50.4,-82.2,999.7,0.2,-0.1,-0.1,-13.4,4.1,-47.9,129.44,-4.64,2.90

accel (millig), gyro (dps), mag (uT), yaw, pitch, roll

On Thu, Feb 14, 2019 at 3:37 PM masrim2000 notifications@github.com wrote:

Yes, almost 2 degrees yaw jitter (approximately from -1 to +1 when at 0)

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-463846760, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qsLh0lm7ck-jvn_3FG2krf4i1HVXks5vNfMhgaJpZM4aglEH .

masrim2000 commented 5 years ago

Yeah, it's definitely not working properly for me. Your ypr have small and similar jitter on all of them. For me, using around 8000 samples I found ypr jitter to be 1.89, 0.15 and 0.8 degrees respectively. That's what I meant by "stable pitch but noisy yaw and roll".

The STM32L4 is only slightly faster than STM32F103 (80 MHz CPU frequency compared to 72 MHz) so there shouldn't be much difference there. I've done multiple calibrations with little to no difference in the jitter I'm seeing. Does the mag calibration actually affect its jitter?

kriswiner commented 5 years ago

The calibration shouldn't affect the jitter when motionless.

The L4 has an FPU, it is 20x faster than the F103 doing sensor fusion. What kinds of fusion rates are you seeing?. Whatever, this doesn't cause mag data jitter. SOmehow, you have a bunch of crappy sensors.

On Thu, Feb 14, 2019 at 4:22 PM masrim2000 notifications@github.com wrote:

Yeah, it's definitely not working properly for me. Your ypr have small and similar jitter on all of them. For me, using around 8000 samples I found ypr jitter to be 1.89, 0.15 and 0.8 degrees respectively. That's what I meant by "stable pitch but noisy yaw and roll".

The STM32L4 is only slightly faster than STM32F103 (80 MHz CPU frequency compared to 72 MHz) so there shouldn't be much difference there. I've done multiple calibrations with little to no difference in the jitter I'm seeing. Does the mag calibration actually affect its jitter?

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-463857489, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qjcgEgocVa6ZmK5Xfc7szsPTe3xFks5vNf3WgaJpZM4aglEH .

masrim2000 commented 5 years ago

Around 2.5-2.7 kHz fusion rate

kriswiner commented 5 years ago

Yes, not too bad and certainly adequate. The L4 can run at 50 kHz, but, of course, 2.7 kHz is enough.

On Thu, Feb 14, 2019 at 5:59 PM masrim2000 notifications@github.com wrote:

Around 2.5-2.7 kHz fusion rate

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-463877276, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1quIAII_9bUEMIQr5Me5wh5L6AJZ4ks5vNhRsgaJpZM4aglEH .

masrim2000 commented 5 years ago

Hi Kris, I hope you're doing well. Both boards I received from you seem to be of high quality and very well designed.

After switching to the ST sensor suite here are the results. I used your set of libraries and example sketch after modifying them so that they work on the STM32F103 (bluepill). After calibrating the accel/gyro and mag and verifying that the mag response circles are round and centered on zero, I got this initial result: madgwick As we can see, pitch and roll are very good. But heading is still very jittery (~3.4 degrees jitter from a couple of minutes of data). This was using Madgwick's algorithm. After that I added Mahony's algorithm to the sketch (for some reason it wasn't there initially, unlike most other sketches) and got the following result: mahony Much better! Heading jitter is now ~1.2 degrees or better. Is this within the expected range for these sensors or can I do better?

I don't really understand why this large difference between the two fusion algorithms, especially since you mentioned in one of the posts that the fusion algorithms isn't one of the primary factors affecting the quality of orientation estimates.

Another thing, I always get considerably less jitter when using Mahony's algorithm (over Madgwick's) and it runs faster than Madgwick's (~2.1kHz fusion rate compared to ~1.6kHz), any particular reason you didn't use it with this sensor suite?

As for the EM7180_MPU9250_BMP280 board you sent me, I still didn't get it to work properly yet. I will post in the appropriate directory in case I don't manage to figure it out. Many thanks.

kriswiner commented 5 years ago

Not sure either why the difference between the two. I usually use Madgwick but eiher will do; I would use the one that gives you best results.

You might try different sample rate settings. I usually use 833 Hz on the accel/gyro and 100 Hz on the mag and get good results. But then I am running at fusion rates of many kHz. In your case at 2 kHz fusion rate, maybe stop the sample rate down to 200 Hz on the gyro or 400 Hz?

On Sun, Mar 3, 2019 at 7:04 AM masrim2000 notifications@github.com wrote:

Hi Kris, I hope you're doing well. Both boards I received from you seem to be of high quality and very well designed.

After switching to the ST sensor suite https://www.tindie.com/products/onehorse/all-st-motion-sensor-breakout-board/ here are the results. I used your set of libraries and example sketch https://github.com/kriswiner/LSM6DSM_LIS2MDL_LPS22HB after modifying them so that they work on the STM32F103 (bluepill). After calibrating the accel/gyro and mag and verifying that the mag response circles are round and centered on zero, I got this initial result: [image: madgwick] https://user-images.githubusercontent.com/47311599/53696227-0bb1ad00-3dd6-11e9-8ecb-08a90f16a736.JPG As we can see, pitch and roll are very good. But heading is still very jittery (~3.4 degrees jitter from a couple of minutes of data). This was using Madgwick's algorithm. After that I added Mahony's algorithm to the sketch (for some reason it wasn't there initially, unlike most other sketches) and got the following result: [image: mahony] https://user-images.githubusercontent.com/47311599/53696324-e2455100-3dd6-11e9-9c74-228615759e5a.JPG Much better! Heading jitter is now ~1.2 degrees or better. Is this within the expected range for these sensors or can I do better?

I don't really understand why this large difference between the two fusion algorithms, especially since you mentioned in one of the posts that the fusion algorithms isn't one of the primary factors affecting the quality of orientation estimates.

Another thing, I always get considerably less jitter when using Mahony's algorithm (over Madgwick's) and it runs faster than Madgwick's (~2.1kHz fusion rate compared to ~1.6kHz), any particular reason you didn't use it with this sensor suite?

As for the EM7180_MPU9250_BMP280 board you sent me, I still didn't get it to work properly yet. I will post in the appropriate directory in case I don't manage to figure it out. Many thanks.

β€” You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/344#issuecomment-469031544, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qvYJX-c-MGew1dksN_wBXv_j7Qghks5vS-RsgaJpZM4aglEH .