Software Magnetometer calibration
Posted: Tue Jan 15, 2013 9:50 am
Hi, in the multiwii code I found this code about Magnetometer
The calibration method is to found a MIN & MAX value of magntic field on each axis, then an average is done and used.
Experience >>
1. with a simple magnetometer calibration at the airfield in other words : start calibration and a simple quad rotating around each axis, then wait the calibration finishes. Then the magnetometer seems working, with the GUI I see a promptly answer for any change of quad orientation and "N", "S", "W" "E" are right.
BUT
GPS POS HOLD work well only if the quad is faced to NORD, if I face it to "W" the HOLD doesn't work and the quad start a large circle.
2. More sophisticated procedure (as readed somewhere in this forum). Quad faced to nord, pitch 45° looking to the ground (I live in Italy Piemonte), the start the magnetometer calibration and for each axis I turn 360° forth and back. Then I wait for the calibration end.
in this way GPS HOLD work well and I face the quad to every direction.
NOTE : during the tests there isn't wind, and each calibration has done in the middle of the air field and far from any metallic structure, the airfiels is grass.
I'm using AIOP V1.1 ALL IN ONE PRO Flight Controller, the sensor are MPU6050 6 axis gyro/accel with Motion Processing Unit, HMC5883L 3-axis digital magnetometer
MS5611-01BA03 highprecision altimeter.
So there is a techinical explanetion about this behaviour ?
Some body could link this post to other with explanations ?
Many thanks
Urkadurka
http://www.gte-elicotteri.it
Code: Select all
if (tCal != 0) {
if ((t - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions
LEDPIN_TOGGLE;
for(axis=0;axis<3;axis++) {
if (magADC[axis] < magZeroTempMin[axis]) magZeroTempMin[axis] = magADC[axis];
if (magADC[axis] > magZeroTempMax[axis]) magZeroTempMax[axis] = magADC[axis];
}
} else {
tCal = 0;
for(axis=0;axis<3;axis++)
global_conf.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis])/2;
writeGlobalSet(1);
}
} else {
#if defined(SENSORS_TILT_45DEG_LEFT)
int16_t temp = ((magADC[PITCH] - magADC[ROLL] )*7)/10;
magADC[ROLL] = ((magADC[ROLL] + magADC[PITCH])*7)/10;
magADC[PITCH] = temp;
#endif
#if defined(SENSORS_TILT_45DEG_RIGHT)
int16_t temp = ((magADC[PITCH] + magADC[ROLL] )*7)/10;
magADC[ROLL] = ((magADC[ROLL] - magADC[PITCH])*7)/10;
magADC[PITCH] = temp;
#endif
}
return 1;
}
#endif
// ************************************************************************************************************
// I2C Compass MAG3110
// ************************************************************************************************************
// I2C adress: 0x0E (7bit)
// ************************************************************************************************************
#if defined(MAG3110)
#define MAG_ADDRESS 0x0E
#define MAG_DATA_REGISTER 0x01
#define MAG_CTRL_REG1 0x10
#define MAG_CTRL_REG2 0x11
void Mag_init() {
delay(100);
i2c_writeReg(MAG_ADDRESS,MAG_CTRL_REG2,0x80); //Automatic Magnetic Sensor Reset
delay(100);
i2c_writeReg(MAG_ADDRESS,MAG_CTRL_REG1,0x11); // DR = 20Hz ; OS ratio = 64 ; mode = Active
delay(100);
magInit = 1;
}
#if !defined(MPU6050_I2C_AUX_MASTER)
void Device_Mag_getADC() {
i2c_getSixRawADC(MAG_ADDRESS,MAG_DATA_REGISTER);
MAG_ORIENTATION( ((rawADC[0]<<8) | rawADC[1]) ,
((rawADC[2]<<8) | rawADC[3]) ,
((rawADC[4]<<8) | rawADC[5]) );
}
#endif
The calibration method is to found a MIN & MAX value of magntic field on each axis, then an average is done and used.
Experience >>
1. with a simple magnetometer calibration at the airfield in other words : start calibration and a simple quad rotating around each axis, then wait the calibration finishes. Then the magnetometer seems working, with the GUI I see a promptly answer for any change of quad orientation and "N", "S", "W" "E" are right.
BUT


2. More sophisticated procedure (as readed somewhere in this forum). Quad faced to nord, pitch 45° looking to the ground (I live in Italy Piemonte), the start the magnetometer calibration and for each axis I turn 360° forth and back. Then I wait for the calibration end.
in this way GPS HOLD work well and I face the quad to every direction.
NOTE : during the tests there isn't wind, and each calibration has done in the middle of the air field and far from any metallic structure, the airfiels is grass.
I'm using AIOP V1.1 ALL IN ONE PRO Flight Controller, the sensor are MPU6050 6 axis gyro/accel with Motion Processing Unit, HMC5883L 3-axis digital magnetometer
MS5611-01BA03 highprecision altimeter.
So there is a techinical explanetion about this behaviour ?
Some body could link this post to other with explanations ?
Many thanks
Urkadurka
http://www.gte-elicotteri.it