Browse Source

AP_Compass: fixed calibration of 5883L compass

this fixes a compass initialisation bug where if the first value from
the compass isn't in the right range we would set bad calibration
scaling factors.

This also changes the maximum acceptable calibration values to 2000,
which is needed for the 5883 compass

pair-programmed-with: Randy Mackay

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2718 f9c3cf11-9bcb-44bc-f272-b75c42450872
mission-4.1.18
tridge60@gmail.com 14 years ago
parent
commit
2605c4b4b2
  1. 14
      libraries/AP_Compass/AP_Compass_HMC5843.cpp

14
libraries/AP_Compass/AP_Compass_HMC5843.cpp

@ -51,11 +51,6 @@ AP_Compass_HMC5843::init() @@ -51,11 +51,6 @@ AP_Compass_HMC5843::init()
}else
product_id = AP_COMPASS_TYPE_HMC5843;
// calibration initialisation
calibration[0] = 1.0;
calibration[1] = 1.0;
calibration[2] = 1.0;
while( success == 0 && numAttempts < 5 )
{
// record number of attempts at initialisation
@ -82,12 +77,17 @@ AP_Compass_HMC5843::init() @@ -82,12 +77,17 @@ AP_Compass_HMC5843::init()
Wire.endTransmission();
delay(10);
// calibration initialisation
calibration[0] = 1.0;
calibration[1] = 1.0;
calibration[2] = 1.0;
// read values from the compass
read();
delay(10);
// calibrate
if( abs(mag_x) > 500 && abs(mag_x) < 1000 && abs(mag_y) > 500 && abs(mag_y) < 1000 && abs(mag_z) > 500 && abs(mag_z) < 1000)
if( abs(mag_x) > 500 && abs(mag_x) < 2000 && abs(mag_y) > 500 && abs(mag_y) < 2000 && abs(mag_z) > 500 && abs(mag_z) < 2000)
{
calibration[0] = fabs(715.0 / mag_x);
calibration[1] = fabs(715.0 / mag_y);
@ -194,4 +194,4 @@ AP_Compass_HMC5843::write_register(int address, byte value) @@ -194,4 +194,4 @@ AP_Compass_HMC5843::write_register(int address, byte value)
Wire.send(value);
Wire.endTransmission();
delay(10);
}
}

Loading…
Cancel
Save