Closed suyashb95 closed 7 years ago
I don't believe there is an offset register for mag offset bias, if there is then yes you can use it. I usually just subtract from the data.
If the mag is not calibrated you will get nonsense for yaw, pitch and roll.
Check the initial values of the bias arrays, they are likely not set correctly.
On Thu, Mar 9, 2017 at 3:03 AM, Suyash Behera notifications@github.com wrote:
Hi Kris, thank you for this amazing library!
I'm using an MPU9150 and the calibration routine from here https://github.com/kriswiner/MPU-9150/issues/3#issuecomment-91378617 to calibrate the magnetometer. However, the min and max values that I'm getting are Max X 7034 Max Y 16416 Max Z 4000 Min X 0 Min Y 0 Min Z 0 When I try different calibration code from RTIMULib https://github.com/RTIMULib/RTIMULib-Arduino/tree/master/ArduinoMagCal, I get the following values
[image: image] https://cloud.githubusercontent.com/assets/7749510/23747172/bfe193d0-04e4-11e7-8e5e-1b2db9b65db2.png
I'm not sure which of these are supposed to be correct. The biases are the averages of the min and max values if I'm not wrong, can I write them directly to the offset register? Or do I have to multiply them with mRes and magCalibration as you have done here https://github.com/kriswiner/MPU-9150/issues/3#issuecomment-91378617?
Right now I'm looking at the output without any magnetometer calibration. Roll and Pitch seem to be correct(Both are 0 when the IMU is on a flat surface) but Yaw is way off. When I rotate the IMU a bit, the yaw, pitch and roll values vary wildly but settle down later. Also, the stability of the readings depends on the starting orientation of the IMU. If I start the AHRS algorithm in certain orientations, yaw pitch and roll just keep oscillating, Will these problems be solved after calibrating the magnetometer or could there be other issues?
ā You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9150/issues/9, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qqzAi__zR4BNyy_bK-WS3izGwdC8ks5rj9x-gaJpZM4MX7_6 .
I believe they are just bytes, but check the data sheet.
On Sat, Mar 25, 2017 at 10:20 AM, Suyash Behera notifications@github.com wrote:
Is the data from the adjustment registers signed or unsigned? Here https://github.com/jrowberg/i2cdevlib/blob/master/Arduino/AK8975/AK8975.cpp#L150 the values are signed 8 bit integers but here https://github.com/kriswiner/MPU-9150/blob/master/MPU9150BasicAHRS.ino#L669 they're 8 bit unsigned integers.
ā You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9150/issues/9#issuecomment-289226038, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1quU4mW2XTY94AFDn5ERcMuGkHfF3ks5rpUzWgaJpZM4MX7_6 .
There's no information about the sign of the adjustment values in the datasheet. They must be unsigned bytes I'm guessing.
This is correct:
void initAK8975A(float * destination) { uint8_t rawData[3]; // x/y/z gyro register data stored here writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x00); // Power down delay(10); writeByte(AK8975A_ADDRESS, AK8975A_CNTL, 0x0F); // Enter Fuse ROM access mode delay(10); readBytes(AK8975A_ADDRESS, AK8975A_ASAX, 3, &rawData[0]); // Read the x-, y-, and z-axis calibration values destination[0] = (float)(rawData[0] - 128)/256. + 1.; // Return x-axis sensitivity adjustment values destination[1] = (float)(rawData[1] - 128)/256. + 1.; destination[2] = (float)(rawData[2] - 128)/256. + 1.; }
On Sat, Mar 25, 2017 at 10:26 AM, Suyash Behera notifications@github.com wrote:
There's no mention about the sign of the adjustment values in the datasheet. They must be unsigned bytes I'm guessing.
ā You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9150/issues/9#issuecomment-289226370, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qtemQ-tZSn2Gmjm0qi8QDZUWpYAAks5rpU4tgaJpZM4MX7_6 .
Thanks for that! š I've calibrated the magnetometer and I'm getting fairly okay results. Only Yaw seems to be problematic, when I change the pitch/roll, yaw changes as well but goes down to its original value after a few seconds. Any idea on what could be causing this? It's affecting the inertial frame acceleration readings since the body frame acceleration has to be rotated according to these angles.
You need to pass the fusion filter the sensor data in the correct order, which is North, East, and Down.
On Mon, Mar 27, 2017 at 10:01 AM, Suyash Behera notifications@github.com wrote:
Thanks for that! š I've calibrated the magnetometer and I'm getting fairly okay results. Only Yaw seems to be problematic, when I change the pitch/roll, yaw changes as well but goes down to its original value after a few seconds. Any idea on what could be causing this? It's affecting the inertial frame acceleration readings since the body frame acceleration has to be rotated according to these angles.
ā You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9150/issues/9#issuecomment-289516859, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qnt9rjWdbZ6MlsUXpJnBrz7xtGxCks5rp-tqgaJpZM4MX7_6 .
I'm afraid I don't understand. I know that the magnetometer's axes aren't aligned with the Gyro/Accel's axes, (X and Y are interchanged). As of now this is how I'm calling the filter function(as it is here).
MadgwickQuaternionUpdate(
acc.x,
acc.y,
acc.z,
gyr.x*PI/180.0f,
gyr.y*PI/180.0f,
gyr.z*PI/180.0f,
mg.y,
mg.x,
mg.z
);
Is this right? You've said that the magnetometer's Z axis is opposite to the Gyro/Accel's Z axis. Will passing
-mg.z
instead of mg.z
fix it?
yes
Thank you for your time :)
(Salute & Respect to Mr. Winer) Yes! Passing -mg.z instead of mg.z fixed it for me as well. So it is Ax Ay Az, Gx Gy Gz, My, Mx, -Mz. I am curious as to why this order differs for everyone? The MPU9250 package is the same for everyone with the misalignment between the Gyro/Acc and the Magnetometer, so is it simply the orientation of the magnetic lines of my location that makes the difference? South African greetings!
This has to do with you choice of North (Ax or Ay) and your choice of convention (ENU or NED or?) so there are a lot of correct combinations. Nothing to do with where on Earth you happen to be.
On Wed, Mar 14, 2018 at 5:43 AM, Kernolsie notifications@github.com wrote:
(Salute & Respect to Mr. Winer) Yes! Passing -mg.z instead of mg.z fixed it for me as well. So it is Ax Ay Az, Gx Gy Gz, My, Mx, -Mz. I am curious as to why this order differs for everyone? The MPU9250 package is the same for everyone with the misalignment between the Gyro/Acc and the Magnetometer, so is it simply the orientation of the magnetic lines of my location that makes the difference? South African greetings!
ā You are receiving this because you modified the open/close state. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9150/issues/9#issuecomment-373007481, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qidS4kd98NJsieQ2C7qsWk057FjMks5teRCHgaJpZM4MX7_6 .
Hi Kris, thank you for this amazing library!
I'm using an MPU9150 and the calibration routine from here to calibrate the magnetometer. However, the min and max values that I'm getting are Max X 7034 Max Y 16416 Max Z 4000 Min X 0 Min Y 0 Min Z 0 When I try different calibration code from RTIMULib, I get the following values
I'm not sure which of these are supposed to be correct. The biases are the averages of the min and max values if I'm not wrong, can I write them directly to the offset register? Or do I have to multiply them with mRes and magCalibration as you have done here?
Right now I'm looking at the output without any magnetometer calibration. Roll and Pitch seem to be correct(Both are 0 when the IMU is on a flat surface) but Yaw is way off. When I rotate the IMU a bit, the yaw, pitch and roll values vary wildly but settle down later. Also, the stability of the readings depends on the starting orientation of the IMU. If I start the AHRS algorithm in certain orientations, yaw pitch and roll just keep oscillating, Will these problems be solved after calibrating the magnetometer or could there be other issues?