kriswiner / MPU9250

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

East-West tilt error. #418

Open FrankKlayton opened 4 years ago

FrankKlayton commented 4 years ago

Hi Kris.

I am currently using MPU9250 (MPU9255 so I get code 0x73) I calibrated accelerometer, gyroscope and magnetometer. All of 9 axis I pass in Madgwick filter and calculate yaw, roll, pitch by Tait-Bryan angles. If MPU9250 horizontal - all tilts is good, yaw is good. If I will tilt MPU9250 east-west position at 5 degrees - yaw will change at ~10 degrees if I will tilt MPU9250 north-south position - yaw will not change What i do wrong? Can you help me?

kriswiner commented 4 years ago

The trick here is to make sure to pass the sensor values to the Madgwick filter as NED values, so aN, aE, aD, gN, gE, gD, etc after choosing (your choice) which board edge will point to North (that is, show quaternion values of 1 0 0 0 when this edge is aligned with true North). Since the sensor axes are generally not co-aligned, you will have to figure out which axis corresponds to which Madgwick filter input. For example, on my board with my choice of North edge, I have used this with success:

MadgwickQuaternionUpdate(-ay, -ax, az, gyPI/180.0f, gxPI/180.0f, -gz*PI/ 180.0f, mx, my, mz);

On Fri, May 29, 2020 at 11:51 PM FrankKlayton notifications@github.com wrote:

Hi Kris.

I am currently using MPU9250 (MPU9255 so I get code 0x73) I calibrated accelerometer, gyroscope and magnetometer. All of 9 axis I pass in Madgwick filter and calculate yaw, roll, pitch by Tait-Bryan angles. If MPU9250 horizontal - all tilts is good, yaw is good. If I will tilt MPU9250 east-west position at 5 degrees - yaw will change at ~10 degrees if I will tilt MPU9250 north-south position - yaw will not change What i do wrong? Can you help me?

— 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/418, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABTDLKXRWG5YRXE7ORNMOGDRUCUGTANCNFSM4NOSD56Q .

FrankKlayton commented 4 years ago

Thanks very much for answer.

"MadgwickQuaternionUpdate(-ay, -ax, az, gyPI/180.0f, gxPI/180.0f, -gz*PI/ 180.0f, mx, my, mz);"

Why you give to filter '-ay' but 'gy' (and '-ax' - 'gx', 'az' - '-gz' )? After that axis will be non co-directed. Sorry for stupid and pester question.

kriswiner commented 4 years ago

You could negate tha a signs to match with g, I would try it. I found better results this way since this amounts to the convention +1 gravity is down not up.

On Sat, May 30, 2020 at 8:24 AM FrankKlayton notifications@github.com wrote:

Thanks very much for answer.

"MadgwickQuaternionUpdate(-ay, -ax, az, gyPI/180.0f, gxPI/180.0f, -gz*PI/ 180.0f, mx, my, mz);"

Why you give to filter '-ay' but 'gy' (and '-ax' - 'gx', 'az' - '-gz' )? After that axis will be non co-directed. Sorry for stupid and pester question.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/418#issuecomment-636346138, or unsubscribe https://github.com/notifications/unsubscribe-auth/ABTDLKVAAJ3CUO42563ZTHTRUEQMNANCNFSM4NOSD56Q .

FrankKlayton commented 4 years ago

I tryed this action and my result is MadgwickQuaternionUpdate(ay, -ax, az, gy, -gx, gz, mx, -my, -mz); My best result with such input data.

+- 1.5 - 2 degrees in roll and pitch. image

Thank you very much. You helped many people, your project with MPU9250 is best.