magnetometer calibration -凯发k8网页登录
magnetometers detect magnetic field strength along a sensor's x,y and z axes. accurate magnetic field measurements are essential for sensor fusion and the determination of heading and orientation.
in order to be useful for heading and orientation computation, typical low cost mems magnetometers need to be calibrated to compensate for environmental noise and manufacturing defects.
ideal magnetometers
an ideal three-axis magnetometer measures magnetic field strength along orthogonal x, y and z axes. absent any magnetic interference, magnetometer readings measure the earth's magnetic field. if magnetometer measurements are taken as the sensor is rotated through all possible orientations, the measurements should lie on a sphere. the radius of the sphere is the magnetic field strength.
to generate magnetic field samples, use the imusensor
object. for these purposes it is safe to assume the angular velocity and acceleration are zero at each orientation.
n = 500; rng(1); acc = zeros(n,3); av = zeros(n,3); q = randrot(n,1); % uniformly distributed random rotations imu = imusensor('accel-mag'); [~,x] = imu(acc,av,q); scatter3(x(:,1),x(:,2),x(:,3)); axis equal title('ideal magnetometer data');
hard iron effects
noise sources and manufacturing defects degrade a magnetometer's measurement. the most striking of these are hard iron effects. hard iron effects are stationary interfering magnetic noise sources. often, these come from other metallic objects on the circuit board with the magnetometer. the hard iron effects shift the origin of the ideal sphere.
imu.magnetometer.constantbias = [2 10 40]; [~,x] = imu(acc,av,q); figure; scatter3(x(:,1),x(:,2),x(:,3)); axis equal title('magnetometer data with a hard iron offset');
soft iron effects
soft iron effects are more subtle. they arise from objects near the sensor which distort the surrounding magnetic field. these have the effect of stretching and tilting the sphere of ideal measurements. the resulting measurements lie on an ellipsoid.
the soft iron magnetic field effects can be simulated by rotating the geomagnetic field vector of the imu to the sensor frame, stretching it, and then rotating it back to the global frame.
nedmf = imu.magneticfield; rsoft = [2.5 0.3 0.5; 0.3 2 .2; 0.5 0.2 3]; soft = rotateframe(conj(q),rotateframe(q,nedmf)*rsoft); for ii=1:numel(q) imu.magneticfield = soft(ii,:); [~,x(ii,:)] = imu(acc(ii,:),av(ii,:),q(ii)); end figure; scatter3(x(:,1),x(:,2),x(:,3)); axis equal title('magnetometer data with hard and soft iron effects');
correction technique
the magcal
function can be used to determine magnetometer calibration parameters that account for both hard and soft iron effects. uncalibrated magnetometer data can be modeled as lying on an ellipsoid with equation
in this equation r is a 3-by-3 matrix, b is a 1-by-3 vector defining the ellipsoid center, x is a 1-by-3 vector of uncalibrated magnetometer measurements, and is a scalar indicating the magnetic field strength. the above equation is the general form of a conic. for an ellipsoid, r must be positive definite. the magcal
function uses a variety of solvers, based on different assumptions about r. in the magcal
function, r can be assumed to be the identity matrix, a diagonal matrix, or a symmetric matrix.
the magcal
function produces correction coefficients that take measurements which lie on an offset ellipsoid and transform them to lie on an ideal sphere, centered at the origin. the magcal
function returns a 3-by-3 real matrix a and a 1-by-3 vector b. to correct the uncalibrated data compute
here x is a 1-by-3 array of uncalibrated magnetometer measurements and m is the 1-by-3 array of corrected magnetometer measurements, which lie on a sphere. the matrix a has a determinant of 1 and is the matrix square root of r. additionally, a has the same form as r : the identity, a diagonal, or a symmetric matrix. because these kinds of matrices cannot impart a rotation, the matrix a will not rotate the magnetometer data during correction.
the magcal
function also returns a third output which is the magnetic field strength . you can use the magnetic field strength to set the expectedmagneticfieldstrength
property of ahrsfilter
.
using the magcal
function
use the magcal
function to determine calibration parameters that correct noisy magnetometer data. create noisy magnetometer data by setting the noisedensity
property of the magnetometer
property in the imusensor
. use the rotated and stretched magnetic field in the variable soft
to simulate soft iron effects.
imu.magnetometer.noisedensity = 0.08; for ii=1:numel(q) imu.magneticfield = soft(ii,:); [~,x(ii,:)] = imu(acc(ii,:),av(ii,:),q(ii)); end
to find the a
and b
parameters which best correct the uncalibrated magnetometer data, simply call the function as:
[a,b,expmfs] = magcal(x); xcorrected = (x-b)*a;
plot the original and corrected data. show the ellipsoid that best fits the original data. show the sphere on which the corrected data should lie.
de = helperdrawellipsoid;
de.plotcalibrated(a,b,expmfs,x,xcorrected,'auto');
the magcal
function uses a variety of solvers to minimize the residual error. the residual error is the sum of the distances between the calibrated data and a sphere of radius expmfs
.
r = sum(xcorrected.^2,2) - expmfs.^2;
e = sqrt(r.'*r./n)./(2*expmfs.^2);
fprintf('residual error in corrected data : %.2f\n\n',e);
residual error in corrected data : 0.01
you can run the individual solvers if only some defects need to be corrected or to achieve a simpler correction computation.
offset-only computation
many mems magnetometers have registers within the sensor that can be used to compensate for the hard iron offset. in effect, the (x-b) portion of the equation above happens on board the sensor. when only a hard iron offset compensation is needed, the a
matrix effectively becomes the identity matrix. to determine the hard iron correction alone, the magcal
function can be called this way:
[aeye,beye,expmfseye] = magcal(x,'eye'); xeyecorrected = (x-beye)*aeye; [ax1,ax2] = de.plotcalibrated(aeye,beye,expmfseye,x,xeyecorrected,'eye'); view(ax1,[-1 0 0]); view(ax2,[-1 0 0]);
hard iron compensation and axis scaling computation
for many applications, treating the ellipsoid matrix as a diagonal matrix is sufficient. geometrically, this means the ellipsoid of uncalibrated magnetometer data is approximated to have its semiaxes aligned with the coordinate system axes and a center offset from the origin. though this is unlikely to be the actual characteristics of the ellipsoid, it reduces the correction equation to a single multiply and single subtract per axis.
[adiag,bdiag,expmfsdiag] = magcal(x,'diag'); xdiagcorrected = (x-bdiag)*adiag; [ax1,ax2] = de.plotcalibrated(adiag,bdiag,expmfsdiag,x,xdiagcorrected,... 'diag');
full hard and soft iron compensation
to force the magcal
function to solve for an arbitrary ellipsoid and produce a dense, symmetric a
matrix, call the function as:
[a,b] = magcal(x,'sym');
auto fit
the 'eye'
, 'diag'
, and 'sym'
flags should be used carefully and the output values inspected. in some cases, there may be insufficient data for a high order ('diag'
or 'sym'
) fit and a better set of correction parameters can be found using a simpler a
matrix. the 'auto'
fit option, which is the default, handles this situation.
consider the case when insufficient data is used with a high order fitter.
xidx = x(:,3) > 100;
xpoor = x(xidx,:);
[apoor,bpoor,mfspoor] = magcal(xpoor,'diag');
there is not enough data spread over the surface of the ellipsoid to achieve a good fit and proper calibration parameters with the 'diag'
option. as a result, the apoor
matrix is complex.
disp(apoor)
0.0000 0.4722i 0.0000 0.0000i 0.0000 0.0000i 0.0000 0.0000i 0.0000 0.5981i 0.0000 0.0000i 0.0000 0.0000i 0.0000 0.0000i 3.5407 0.0000i
using the 'auto'
fit option avoids this problem and finds a simpler a
matrix which is real, symmetric, and positive definite. calling magcal
with the 'auto'
option string is the same as calling without any option string.
[abest,bbest,mfsbest] = magcal(xpoor,'auto');
disp(abest)
1 0 0 0 1 0 0 0 1
comparing the results of using the 'auto'
fitter and an incorrect, high order fitter show the perils of not examining the returned a
matrix before correcting the data.
de.comparebest(abest,bbest,mfsbest,apoor,bpoor,mfspoor,xpoor);
calling the magcal
function with the 'auto'
flag, which is the default, will try all possibilities of 'eye'
, 'diag'
and 'sym'
searching for the a
and b
which minimizes the residual error, keeps a
real, and ensures r is positive definite and symmetric.
conclusion
the magcal
function can give calibration parameters to correct hard and soft iron offsets in a magnetometer. calling the function with no option string, or equivalently the 'auto'
option string, produces the best fit and covers most cases.