Introduction
It can be difficult to get useful data from a magnetometer. It can be especially difficult if the data is used to estimate the yaw attitude of the vehicle. For example, the sensor may indicate the proper direction for certain attitudes, but a wrong direction for other attitudes. Or, the yaw estimate may be accurate one day and off the next.
In order for magnetometer data to yield the yaw attitude of a vehicle, the magnetometer must measure the direction of the geomagnetic field (i.e. the Earth's magnetic field). The geomagnetic field points north (more or less) and has been used for navigation for hundreds of years. The challenge is that the geomagnetic field is relatively weak. It is common for the geomagnetic field to be distorted or obscured by extraneous magnetic sources in the vicinity of the magnetometer. The purpose of magnetometer calibration is to extract an observation of the geomagnetic field vector from the sensor’s output, which is corrupted by various errors.
Over the last several years, I have tinkered with the AK8963 magnetometer, which is part of the MPU-9250 IMU. Through trial-and-error, I eventually arrived at a dependable calibration procedure. The calibration procedure is repeatable and produces sufficiently accurate estimates of the yaw attitude. It is typical for the yaw attitude to have less than 2 degrees of error, provided the aircraft is in the wings-level configuration. Because of this work, the magnetometer now serves as the primary yaw attitude sensor within our autopilot system.
In this article, I want to share four lessons I learned while integrating the magnetometer into an autopilot system. These lessons are probably familiar to those who work with magnetometers. However, for those who are new to magnetometers, this article may alert you to some common pitfalls. The four lessons are:
- Artificial errors impose special considerations on magnetometer calibration.
- Autocalibration methods have a fundamental flaw.
- Keep it simple with the compass swinging method.
- The throttle command can be related to a magnetometer bias.
In the remainder of this article, I will expand upon each of the previous points. For a more mathematical treatment of the proposed calibration procedure, the reader is referred to the attached PDF.
Artificial errors impose special considerations on magnetometer calibration
Magnetometers are subject to two types of errors: instrument errors and artificial errors. Instrument errors are associated with the sensor itself. Instrument errors are less noticeable in high-grade sensors than low-grade sensors. Artificial errors are extraneous magnetic sources that compete with the geomagnetic field. Artificial errors are associated with the environment. For this reason, you should calibrate the magnetometer in an environment that is similar to the sensor's operative environment. Practically, this means calibrating the sensor in its final configuration on the vehicle. This also means calibrating the sensor outdoors, away from buildings and power lines, which may distort the geomagnetic field. While it may be more convenient to calibrate an isolated magnetometer on a workbench, the calibration would likely become obsolete as soon as the magnetometer is mounted on the vehicle.
It is worth emphasizing that artificial errors are not associated with the sensor itself. Consequently, you cannot fix artificial errors by getting a better sensor. You fix artificial errors by (i) shielding/isolating the extraneous sources or (ii) removing the effects of the artificial errors from the data. In this work, we take the latter approach.
That said, the choice of magnetometer is still important. The full-scale range (FSR) of the sensor is particularly important. You don't want a sensor with a FSR that is orders-of-magnitude greater than the magnitude of the quantity of interest. This is because range and resolution are competing factors: what you gain in range you lose in resolution. For our application (vehicle state estimation), the quantity of interest is the geomagnetic field, the magnitude of which is about 0.5 Gauss. The AK8963 is a poor choice for our application because its FSR is 50 Gauss, which is 100x greater than the quantity of interest!
Autocalibration methods have a fundamental flaw
An autocalibration method determines the calibration parameters solely from magnetometer measurements. This feature makes it easy to collect the calibration data. Undoubtedly, the ease of data collection contributes to the popularity of a particular autocalibration method, the ellipsoid-fitting method. However, it can be shown that autocalibration methods are unable to correct for misalignment between the magnetometer and other inertial sensors [1]. Furthermore, it can be shown that misalignment is detrimental to attitude estimation [2]. In order to correct for magnetometer misalignment, additional sensors must be used. The theoretical flaw with autocalibration methods has real-world ramifications. In my experience, I have yet to see the ellipsoid-fitting method produce satisfactory estimates of the yaw attitude.
Keep it simple with the compass swinging method
Alternatives to the ellipsoid-fitting method include the dot-product invariance (DPI) method [3] and the compass swinging method. These alternative methods correct for misalignment by assimilating data from an additional sensor. The DPI method assimilates accelerometer data. The swinging method assimilates data from an "imaginary" magnetometer. We obtain data from the "imaginary" magnetometer by deducing the components of the geomagnetic field based on the orientation of the vehicle with respect to a compass rose. The mathematical details for all three calibration methods are included in the attached PDF.
The calibration procedure that I recommend applies the DPI method and the compass swinging method in succession. The DPI method is used to obtain a crude 3D calibration. The swinging method is used to enhance the measurement accuracy in the wings-level position. Of course, the calibration accuracy will decrease as the vehicle departs from the wings-level position. However, it is reasonable to assume the vehicle will remain close to the wings-level position during constant-altitude operations. Furthermore, deviations from the wings-level position are bounded due to roll and pitch constraints.
Ideally, the magnetometer would be well-calibrated after applying the DPI method. In practice, however, the estimated yaw angle can have up to 10 degrees of error. The error is linked to the off-diagonal elements of the matrix that appears in the inverse error model. The off-diagonal elements are difficult to observe using the DPI method. That is, the off-diagonal elements vary from run to run. For this reason, the swinging method is needed as an additional calibration step.
The throttle command can be related to a magnetometer bias
An electrical current will generate a magnetic field according to the Biot-Savart law (see this HyperPhysics article). A large current close to the magnetometer will bias the sensor and alter the estimated yaw attitude. A common source of such a current is the current drawn by the electric powertrain of the aircraft. The current-induced bias can be canceled by subtracted an estimated bias from the magnetometer readings. The estimated bias is proportional to the current. The proportionality constants can be estimated from system identification tests.
Of course, the previous solution requires a current sensor on the powertrain. The current sensor may be avoided by recognizing that the current is related to the throttle command. Using physical models of the UAV's powertrain (see the figure above), we can show that the current-induced bias is proportional to the square of the throttle command [4]. The figure below plots the magnetometer bias versus throttle command. The variable h3 denotes the component of the current-induced magnetometer bias along the z axis of the sensor. Overlaying the data is the quadratic model predicted by the powertrain analysis.
Conclusion
In conclusion, this article offers four insights on magnetometer calibration. First, we show that artificial errors impose special considerations on magnetometer calibration. Second, we caution the reader about autocalibration methods, such as the ellipsoid-fitting method. Third, we propose a calibration procedure that combines the DPI method and the swinging method. Finally, we propose a quadratic model for throttle-induced magnetometer biases.
magnetometer_calibration_procedure.pdf
References
[1] J. L. Crassidis, K.-L. Lai, and R. R. Harman, “Real-time attitude-independent three-axis magnetometer calibration,” J. Guid., Control Dyn., vol. 28, no. 1, pp. 115–120, 2005.
[2] D. Gebre-Egziabher, “Magnetometer autocalibration leveraging measurement locus constraints,” J. Aircr., vol. 44, no. 4, pp. 1361–1368, Jul. 2007.
[3] X. Li and Z. Li, “A new calibration method for tri-axial field sensors in strap-down navigation systems,” Meas. Sci. Technol., vol. 23, no. 10, pp. 105105-1–105105-6, 2012.
[4] M. Silic and K. Mohseni, “Correcting current-induced magnetometer errors on UAVs: An online model-based approach,” IEEE Sens. J., vol. 20, no. 2, pp. 1067–1076, 2020.
Comments