kriswiner / MPU9250

Arduino sketches for MPU9250 9DoF with AHRS sensor fusion
1.04k stars 470 forks source link

Magnetometer calibration question #50

Open 1994james opened 8 years ago

1994james commented 8 years ago

Hello, this might have a very obvious question, but I've plotted my magnetometer values on a 3D scatter graph, the next step in the wiki is the use the code you state, which is this:

void magcalMPU9250(float * dest1, float * dest2) { uint16_t ii = 0, sample_count = 0; int32_t mag_bias[3] = {0, 0, 0}, mag_scale[3] = {0, 0, 0}; int16_t mag_max[3] = {0xF000, 0xF000, 0xF000}, mag_min[3] = {0x7FFF, 0x7FFF, 0x7FFF}, mag_temp[3] = {0, 0, 0};

Serial.println("Mag Calibration: Wave device in a figure eight until done!"); delay(4000);

sample_count = 128; for(ii = 0; ii < sample_count; ii++) { MPU9250readMagData(mag_temp); // Read the mag data
for (int jj = 0; jj < 3; jj++) { if(mag_temp[jj] > mag_max[jj]) mag_max[jj] = mag_temp[jj]; if(mag_temp[jj] < mag_min[jj]) mag_min[jj] = mag_temp[jj]; } delay(135); // at 8 Hz ODR, new mag data is available every 125 ms }

// Get hard iron correction mag_bias[0] = (mag_max[0] + mag_min[0])/2; // get average x mag bias in counts mag_bias[1] = (mag_max[1] + mag_min[1])/2; // get average y mag bias in counts mag_bias[2] = (mag_max[2] + mag_min[2])/2; // get average z mag bias in counts

dest1[0] = (float) mag_bias[0]_MPU9250mRes_MPU9250magCalibration[0]; // save mag biases in G for main program dest1[1] = (float) mag_bias[1]_MPU9250mRes_MPU9250magCalibration[1];
dest1[2] = (float) mag_bias[2]_MPU9250mRes_MPU9250magCalibration[2];

// Get soft iron correction estimate mag_scale[0] = (mag_max[0] - mag_min[0])/2; // get average x axis max chord length in counts mag_scale[1] = (mag_max[1] - mag_min[1])/2; // get average y axis max chord length in counts mag_scale[2] = (mag_max[2] - mag_min[2])/2; // get average z axis max chord length in counts

float avg_rad = mag_scale[0] + mag_scale[1] + mag_scale[2]; avg_rad /= 3.0;

dest2[0] = avg_rad/((float)mag_scale[0]); dest2[1] = avg_rad/((float)mag_scale[1]); dest2[2] = avg_rad/((float)mag_scale[2]);

Serial.println("Mag Calibration done!"); }

My question is where does this go? Do I start a new sketch with it, or add it into existing one? Or am I wrong and confused all together? Thanks for the help

kriswiner commented 8 years ago

Add it as a function in your sketch and then subtract the offset biases from subsequent mag data.

See:

https://github.com/kriswiner/MPU-9250/blob/master/MPU9250_MS5637_AHRS_t3.ino

1994james commented 8 years ago

Hey, so I've added the calibration code to the 9250 normal code. I have re-done the figure 8 test to get new data to plot it. I've plotted 2 calibrated test to prove consistency. These are my original plot and the 2 cal ones. Do these look correct to you, as far as you can see? Thank you

uncal calib1 calib2

kriswiner commented 8 years ago

None of these looks that great. Are you sure you are implementing the function correctly? You need to move the sensor all around to sample as much of the response surface as you can while calibration data is being collected. The result should be a more or less spherical cloud of points that, when properly offset bias calibrated, are centered at the origin.

1994james commented 8 years ago

This is how im testing your code -- https://github.com/1994james/Calib9250/blob/master/_9250caled.ino does everything look ok with that?

this is what is says when i run it

MPU9250 is online... x-axis self test: acceleration trim within : 0.5% of factory value y-axis self test: acceleration trim within : 2.3% of factory value z-axis self test: acceleration trim within : -1.3% of factory value x-axis self test: gyration trim within : 1.0% of factory value y-axis self test: gyration trim within : -0.0% of factory value z-axis self test: gyration trim within : -0.5% of factory value MPU9250 initialized for active data mode.... AK8963 I AM 48 I should be 48 AK8963 initialized for active data mode.... Mag Calibration: Wave device in a figure eight until done! mag x min/max: 255 -180 mag y min/max: 255 -353 mag z min/max: 416 -64 Mag Calibration done! AK8963 mag biases (mG) 0.00 0.00 0.00 AK8963 mag scale (mG) 1.17 0.83 1.06 X-Axis sensitivity adjustment value 1.19 Y-Axis sensitivity adjustment value 1.19 Z-Axis sensitivity adjustment value 1.15

kriswiner commented 8 years ago

This is wrong:

mag x min/max: 255

1994james commented 8 years ago

What do I have to change to correct this? Isn't that calculated with the calibrating function? Or am I wrong?

kriswiner commented 8 years ago

This is how I do it:

https://github.com/kriswiner/MPU-9250/blob/master/MPU9250_MS5637_AHRS_t3.ino

and this is what the results typically are:

https://github.com/kriswiner/MPU-6050/wiki/Simple-and-Effective-Magnetometer -Calibration

I am not sure what else I can say.

-----Original Message----- From: 1994james [mailto:notifications@github.com] Sent: March 10, 2016 3:07 PM To: kriswiner/MPU-9250 Cc: Kris Winer Subject: Re: [MPU-9250] Magnetometer calibration question (#50)

What do I have to change to correct this? Isn't that calculated with the calibrating function? Or am I wrong?

Reply to this email directly or view it on GitHub https://github.com/kriswiner/MPU-9250/issues/50#issuecomment-195091358 . https://github.com/notifications/beacon/AGY1qt4LTpVuOsEtHCKT1zPOhxm2-3Kcks5 psKQFgaJpZM4HsNq7.gif

empyre commented 8 years ago

I think the problem is here https://github.com/kriswiner/MPU-9250/blob/master/MPU9250_MS5637_AHRS_t3.ino#L1004 line 1004

int16_t mag_max[3] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, mag_temp[3] = {0, 0, 0};

For int16_t the MAX and MIN values are 0x7FFF(32,767) and 0x8000(-32,768)

So the initial value for mag_max and mag_min would be like this int16_t mag_max[3] = {0x8000, 0x8000, 0x8000}, mag_min[3] = {0x7FFF, 0x7FFF, 0x7FFF}, mag_temp[3] = {0, 0, 0};

I also find I need to change https://github.com/kriswiner/MPU-9250/blob/master/MPU9250_MS5637_AHRS_t3.ino#L506 MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, my, mx, mz); to MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f, -my, -mx, mz); to make the fusion function work fine.

kriswiner commented 8 years ago

Yes, I think this is right, but it shouldn't matter. That is, one could use 0x0000 for both min and max and it would only matter when the offset is so bat that the mag values don't cross zero. But technically you are correct here. The way you feed the axis values into the Madgwick (or Mahony) function depend on your convention for which axis is chosen to be North. If your choice works for your MPU9250 sensor board, that is the one to use.

Kris

-----Original Message----- From: empyre [mailto:notifications@github.com] Sent: March 10, 2016 7:21 PM To: kriswiner/MPU-9250 Cc: Kris Winer Subject: Re: [MPU-9250] Magnetometer calibration question (#50)

I think the problem is here https://github.com/kriswiner/MPU-9250/blob/master/MPU9250_MS5637_AHRS_t3.ino

L1004

line 1004

int16_t mag_max[3] = {0xFF, 0xFF, 0xFF}, mag_min[3] = {0x7F, 0x7F, 0x7F}, mag_temp[3] = {0, 0, 0};

For int16_t the MAX and MIN values are 0x7FFF(32,767) and 0x8000(-32,768)

So the initial value for mag_max and mag_min would be like this int16_t mag_max[3] = {0x8000, 0x8000, 0x8000}, mag_min[3] = {0x7FFF, 0x7FFF, 0x7FFF}, mag_temp[3] = {0, 0, 0};

I also find I need to change https://github.com/1994james/Calib9250/blob/master/_9250caled.ino#L368 MahonyQuaternionUpdate(ax, ay, az, gx_PI/180.0f, gy_PI/180.0f, gz_PI/180.0f, my, mx, mz); to MahonyQuaternionUpdate(ax, ay, az, gx_PI/180.0f, gy_PI/180.0f, gz_PI/180.0f, -my, -mx, mz); to make the fusion function work fine.

Reply to this email directly or view it on GitHub https://github.com/kriswiner/MPU-9250/issues/50#issuecomment-195161026 . https://github.com/notifications/beacon/AGY1qrQst5QMZAneYAjOWwyerrNOy3pTks5 psN-ogaJpZM4HsNq7.gif

1994james commented 8 years ago

So i looked through your code and made a couple of changes to mine based on that. when i run it, I now get this back in the serial monitor --

MPU9250 I AM 73 I should be 73 MPU9250 is online... x-axis self test: acceleration trim within : -2.9% of factory value y-axis self test: acceleration trim within : 1.4% of factory value z-axis self test: acceleration trim within : 1.4% of factory value x-axis self test: gyration trim within : 0.0% of factory value y-axis self test: gyration trim within : -0.1% of factory value z-axis self test: gyration trim within : 0.1% of factory value Calibrate gyro and accel accel biases (mg) 40.59 -97.66 16.24 gyro biases (dps) 3.10 -1.26 3.16 MPU9250 initialized for active data mode.... AK8963 I AM 48 I should be 48 AK8963 initialized for active data mode.... Mag Calibration: Wave device in a figure eight until done! mag x min/max: 282 -216 mag y min/max: 105 -478 mag z min/max: 364 -43 Mag Calibration done! AK8963 mag biases (mG) 58.76 -332.27 275.51 AK8963 mag scale (mG) 0.99 0.85 1.22 X-Axis sensitivity adjustment value 1.19 Y-Axis sensitivity adjustment value 1.19 Z-Axis sensitivity adjustment value 1.15

so its actually giving me mag biases now rather than 0. I plotted these the values after this and got this -

newest

As you can see there are still outliers and there was around 5 points that were in the 1000-2000 region which isn't shown. This looks better than the previous one but im guessing its still not correct? Also thank you for the help.

kriswiner commented 8 years ago

This seems much better.

1994james commented 8 years ago

Awesome.

Next problem, my yaw does not seem responsive to movement in the y axis. My roll and pitch seem to be swapped. And lastly my ypr values are roughly 130,3,3 at rest. Gx,Gy and gz are all around 0, does that means it's the Accel bias? Thanks

kriswiner commented 8 years ago

You might have to change the way you are feeding the sensor values into the Madgwick algorithm. See:

https://github.com/kriswiner/EM7180_SENtral_sensor_hub/wiki/C.-Managing-the- Configuration-File

-----Original Message----- From: 1994james [mailto:notifications@github.com] Sent: March 11, 2016 8:31 PM To: kriswiner/MPU-9250 Cc: Kris Winer Subject: Re: [MPU-9250] Magnetometer calibration question (#50)

Awesome.

Next problem, my yaw does not seem responsive to movement in the y axis. My roll and pitch seem to be swapped. And lastly my ypr values are roughly 130,3,3 at rest. Gx,Gy and gz are all around 0, does that means it's the Accel bias? Thanks

Reply to this email directly or view it on GitHub https://github.com/kriswiner/MPU-9250/issues/50#issuecomment-195658590 . https://github.com/notifications/beacon/AGY1qgIVirVkbVpwlsWH96fA4K7rnfahks5 pskGggaJpZM4HsNq7.gif

1994james commented 8 years ago

The website is hasn't accepted my registration for the toolkit yet, and im a little confused about what you mean. I get what the page says about what axis faces north, but when you say change the way you are feeding the sensor values into the Madgwick algorithm, do you mean change the line MadgwickQuaternionUpdate(ax, ay, az, gx_PI/180.0f, gy_PI/180.0f, gz*PI/180.0f, my, mx, mz);

or is it more complex than that? thanks

kriswiner commented 8 years ago

I mean mean change the line MadgwickQuaternionUpdate(ax, ay, az, gxPI/180.0f, gyPI/180.0f, gz*PI/180.0f, my, mx, mz);

Pick a convention (i.e., NED), pick an axis for North, then make sure the data is fed into the Madgwick function correctly for this choice.

1994james commented 8 years ago

so if i wanted north to be at the y axis, judging from the link, it should be this?

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

kriswiner commented 8 years ago

Actually, after a little more thought, I think this is correct for the MPU9250:

// Sensors x (y)-axis of the accelerometer/gyro is aligned with the y (x)axis of the magnetometer; // the magnetometer z-axis (+ down) is misaligned with z-axis (+ up) of accelerometer and gyro! // We have to make some allowance for this orientation mismatch in feeding the output to the quaternion filter. // We will assume that +y accel/gyro is North, then x accel/gyro is East. So if we want te quaternions properly aligned // we need to feed into the madgwick function Ay, Ax, -Az, Gy, Gx, -Gz, Mx, My, and Mz. But because gravity is by convention // positive down, we need to invert the accel data, so we pass -Ay, -Ax, Az, Gy, Gx, -Gz, Mx, My, and Mz into the Madgwick // function to get North along the accel +y-axis, East along the accel +x-axis, and Down along the accel -z-axis. // This orientation choice can be modified to allow any convenient (non-NED) orientation convention. // This is ok by aircraft orientation standards! // Pass gyro rate as rad/s MadgwickQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f, gx_PI/180.0f, -gz_PI/180.0f, mx, my, mz); // if(passThru)MahonyQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f, gx_PI/180.0f, -gz_PI/180.0f, mx, my, mz);

Kris

wewillfindyou commented 7 years ago

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

void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) {

so this should be correct i guess.

another question: I think, you are not using mahony in your madwick. but madwick changed his algo to mahony and is just making the magnet implementation by his algo. do you use the newest (2013) madwick algo?

kriswiner commented 7 years ago

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

is not correct, accel/gyro x is mag y, accel/gyro z if mag -z, etc. Check data sheet. Enter sensor data as North, East, Down for all three sensors.

On Fri, Mar 17, 2017 at 9:52 AM, wewillfindyou notifications@github.com wrote:

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

void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) {

so this should be correct i guess.

another question: you are using no mahony in your madwick. but madwick changed his algo to mahony and is just making the magnet implementation by his algo. do you use the newest (2013) madwick algo?

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9250/issues/50#issuecomment-287409870, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qjrDTAYW1R-ATPkxf6lQ2OfvN6nLks5rmrpWgaJpZM4HsNq7 .

wewillfindyou commented 7 years ago

this is yours: MadgwickQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f, gx_PI/180.0f, -gz_PI/180.0f, mx, my, mz); // this is mine: mpu9250.MadgwickQuaternionUpdate(-ax, -ay, +az, gxPI/180.0f, gyPI/180.0f, -gz*PI/180.0f, my, mx, mz);

I am changing the position while reading the sensor values:

mpu9250.readGyroData(gyroCount);  // Read the x/y/z adc values
// Calculate the gyro value into actual degrees per second
gy = (float)gyroCount[0]*gRes - gyroBias[0];  //gx// 
gx = (float)gyroCount[1]*gRes - gyroBias[1];  //gy
gz = (float)gyroCount[2]*gRes - gyroBias[2];   

mpu9250.readAccelData(accelCount);  // Read the x/y/z adc values   
// Now we'll calculate the accleration value into actual g's
ay = (float)accelCount[0]*aRes - accelBias[0];  //ax 
ax = (float)accelCount[1]*aRes - accelBias[1];   //ay
az = (float)accelCount[2]*aRes - accelBias[2];   //az

First i was thinking my sensor is wrong placed direction. now it makes sense, why i had to change the order of values reading from the sensor.

And still my magsensor positions were wrong.

kriswiner commented 7 years ago

Glad it works for you.

On Sat, Mar 18, 2017 at 3:06 AM, wewillfindyou notifications@github.com wrote:

this is yours: MadgwickQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f, gx_PI/180.0f, -gz_PI/180.0f, mx, my, mz); // this is mine: mpu9250.MadgwickQuaternionUpdate(-ax, -ay, +az, gxPI/180.0f, gyPI/180.0f, -gz*PI/180.0f, my, mx, mz);

I am changing the position the position while reading the sensor values: mpu9250.readGyroData(gyroCount); // Read the x/y/z adc values // Calculate the gyro value into actual degrees per second gy = (float)gyroCount[0]gRes - gyroBias[0]; //gx// gx = (float)gyroCount[1]gRes - gyroBias[1]; //gy gz = (float)gyroCount[2]*gRes - gyroBias[2];

mpu9250.readAccelData(accelCount); // Read the x/y/z adc values // Now we'll calculate the accleration value into actual g's ay = (float)accelCount[0]aRes - accelBias[0]; //ax ax = (float)accelCount[1]aRes - accelBias[1]; //ay az = (float)accelCount[2]*aRes - accelBias[2]; //az

First i was thinking my sensor is wrong placed direction. now it makes sense, why i had to change the order of values reading from the sensor.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU-9250/issues/50#issuecomment-287532005, or mute the thread https://github.com/notifications/unsubscribe-auth/AGY1qhShD0IdmEzXD3rjAuUU9EzNsmhxks5rm6y8gaJpZM4HsNq7 .

maopal commented 3 years ago

test test3d

Ignore the title of the plots These plots are my attempt to account for soft & hard iron biases . Hi Kris, does this magnetometer look calibrated for the madgwickupdatequaternion?

Thanks again

kriswiner commented 3 years ago

https://github.com/kriswiner/MPU6050/wiki/Simple-and-Effective-Magnetometer-Calibration

On Sun, Feb 21, 2021 at 5:00 AM palemao notifications@github.com wrote:

[image: test] https://user-images.githubusercontent.com/74777355/108625726-57871200-7444-11eb-90a5-77fa9c73bd06.png [image: test3d] https://user-images.githubusercontent.com/74777355/108625727-581fa880-7444-11eb-87d0-5d8835314a55.png

Hi Kris, does this magnetometer look calibrated for the madgwickupdatequaternion?

Thanks again

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