Skip to content

Magnetometer Calibration Module Documentation

Optional Dependencies Required

Some magnetometer calibration methods (MAGYC and MagFactor3) require jax and gtsam, which are not installed by default. Install the calibration extra to enable them:

pip install navlib[calibration]

On Python >= 3.12, gtsam requires a pre-release build:

pip install navlib[calibration] --pre

If using uv:

[tool.uv]
prerelease = "allow"

This module contains functions to calibrate magnetometers using various methods based on research papers and algorithms.

Functions:

Name Description
cal_mag_ellipsoid_fit

Standard ellipsoid fit method.

cal_mag_ellipsoid_fit_fang

Ellipsoid fit method by Fang et al. [1]

cal_mag_magfactor3

Factor graph based approach to full-magnetometer calibration.

cal_mag_twostep_hi

TWOSTEP method for hard-iron estimation [2].

cal_mag_twostep_hsi

TWOSTEP method for hard-iron and soft-iron estimation [2].

cal_mag_sar_ls

The linear least squares for sensor bias calibration [3].

cal_mag_sar_kf

The Kalman filter for sensor bias calibration [3].

cal_mag_sar_aid

The adaptive identification for sensor bias calibration [3].

cal_mag_sphere_fit

Standard sphere fit method.

cal_mag_magyc_ls

MAGYC-LS method [4].

cal_mag_magyc_nls

MAGYC-NLS method [4].

cal_mag_magyc_bfg

MAGYC-BFG method [4].

cal_mag_magyc_ifg

MAGYC-IFG method [4].

References

[1] Section (III) in J. Fang, H. Sun, J. Cao, X. Zhang, and Y. Tao, “A novel calibration method of magnetic compass based on ellipsoid fitting,” IEEE Transactions on Instrumentation and Measurement, vol. 60, no. 6, pp. 2053--2061, 2011.

[2] Alonso, R. Shuster, M.D. (2002a). TWOSTEP: A fast, robust algorithm for attitude-independent magnetometer-bias determination. Journal of the Astronautical Sciences, 50(4):433-452.

[3] Troni, G. and Whitcomb, L. L. (2019). Field sensor bias calibration with angular-rate sensors: Theory and experimental evaluation with application to magnetometer calibration. IEEE/ASME Transactions on Mechatronics, 24(4):1698--1710.

[4] Rodríguez-Martínez, S., & Troni, G. (2025). Full Magnetometer and Gyroscope Bias Estimation Using Angular Rates: Theory and Experimental Evaluation of a Factor Graph-Based Approach. IEEE Journal of Oceanic Engineering.

The ellipsoid fit method is based on the fact that the error model of a magnetic compass is an ellipsoid, and a constraint least-squares method is adopted to estimate the parameters of an ellipsoid by rotating the magnetic compass in various random orientations.

For further details about the implementation, refer to Aleksandr Bazhin Github repository, where he ports to python [matlab's ellipsoid fit].(http://www.mathworks.com/matlabcentral/fileexchange/24693-ellipsoid-fit)

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required

Returns:

Name Type Description
hard_iron ndarray

Hard iron bias as a (3,) numpy array.

soft_iron ndarray

Soft iron matrix as a (3, 3) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

Raises:

Type Description
TypeError

If the input is not a numpy array or a list.

ValueError

If the input is not a 3xN or Nx3 numpy array.

Source code in navlib/cal/cal_mag.py
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
def cal_mag_ellipsoid_fit(
    magnetic_field: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:
    """
    The ellipsoid fit method is based on the fact that the error model of a magnetic
    compass is an ellipsoid, and a constraint least-squares method is adopted to
    estimate the parameters of an ellipsoid by rotating the magnetic compass in
    various random orientations.

    For further details about the implementation, refer to Aleksandr Bazhin [Github
    repository](https://github.com/aleksandrbazhin/ellipsoid_fit_python), where he
    ports to python [matlab's ellipsoid fit].(http://www.mathworks.com/matlabcentral/fileexchange/24693-ellipsoid-fit)

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.

    Returns:
        hard_iron (numpy.ndarray): Hard iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Soft iron matrix as a (3, 3) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.

    Raises:
        TypeError: If the input is not a numpy array or a list.
        ValueError: If the input is not a 3xN or Nx3 numpy array.
    """
    # Check if the input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The input must be a numpy array or a list.")

    # Check if the input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The input must be a 3xN or Nx3 numpy array.")

    # Force the array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Compute magnetic field calibration
    x, y, z = magnetic_field[:, 0], magnetic_field[:, 1], magnetic_field[:, 2]

    d_matrix = np.array(
        [
            x * x + y * y - 2 * z * z,
            x * x + z * z - 2 * y * y,
            2 * x * y,
            2 * x * z,
            2 * y * z,
            2 * x,
            2 * y,
            2 * z,
            1 - 0 * x,
        ]
    )
    d2 = np.array(x * x + y * y + z * z).T
    u = np.linalg.solve(d_matrix.dot(d_matrix.T), d_matrix.dot(d2))
    a = np.array([u[0] + 1 * u[1] - 1])
    b = np.array([u[0] - 2 * u[1] - 1])
    c = np.array([u[1] - 2 * u[0] - 1])
    v = np.concatenate([a, b, c, u[2:]], axis=0).flatten()
    a_matrix = np.array(
        [
            [v[0], v[3], v[4], v[6]],
            [v[3], v[1], v[5], v[7]],
            [v[4], v[5], v[2], v[8]],
            [v[6], v[7], v[8], v[9]],
        ]
    )

    center = np.linalg.solve(-a_matrix[:3, :3], v[6:9])

    translation_matrix = np.eye(4)
    translation_matrix[3, :3] = center.T

    r_matrix = translation_matrix.dot(a_matrix).dot(translation_matrix.T)

    evals, evecs = np.linalg.eig(r_matrix[:3, :3] / -r_matrix[3, 3])
    evecs = evecs.T

    radii = np.sqrt(1.0 / np.abs(evals))
    radii *= np.sign(evals)

    a, b, c = radii
    r = (a * b * c) ** (1.0 / 3.0)
    D = np.array([[r / a, 0.0, 0.0], [0.0, r / b, 0.0], [0.0, 0.0, r / c]])
    transformation = evecs.dot(D).dot(evecs.T)

    hard_iron = center.reshape(3, 1)
    soft_iron = transformation.reshape(3, 3)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    return hard_iron.flatten(), soft_iron, calibrated_magnetic_field

The ellipsoid fit method is based on the fact that the error model of a magnetic compass is an ellipsoid, and a constraint least-squares method is adopted to estimate the parameters of an ellipsoid by rotating the magnetic compass in various random orientations.

For further details about the implementation, refer to section (III) in J. Fang, H. Sun, J. Cao, X. Zhang, and Y. Tao, “A novel calibration method of magnetic compass based on ellipsoid fitting,” IEEE Transactions on Instrumentation and Measurement, vol. 60, no. 6, pp. 2053--2061, 2011.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required

Returns:

Name Type Description
hard_iron ndarray

Hard iron bias as a (3,) numpy array.

soft_iron ndarray

Soft iron matrix as a (3, 3) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

Raises:

Type Description
TypeError

If the input is not a numpy array or a list.

ValueError

If the input is not a 3xN or Nx3 numpy array.

RuntimeWarning

If no positive eigenvalues are found.

Source code in navlib/cal/cal_mag.py
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
def cal_mag_ellipsoid_fit_fang(
    magnetic_field: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:
    """
    The ellipsoid fit method is based on the fact that the error model of a magnetic
    compass is an ellipsoid, and a constraint least-squares method is adopted to
    estimate the parameters of an ellipsoid by rotating the magnetic compass in
    various random orientations.

    For further details about the implementation, refer to section (III) in J. Fang,
    H. Sun, J. Cao, X. Zhang, and Y. Tao, “A novel calibration method of magnetic
    compass based on ellipsoid fitting,” IEEE Transactions on Instrumentation
    and Measurement, vol. 60, no. 6, pp. 2053--2061, 2011.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.

    Returns:
        hard_iron (numpy.ndarray): Hard iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Soft iron matrix as a (3, 3) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.

    Raises:
        TypeError: If the input is not a numpy array or a list.
        ValueError: If the input is not a 3xN or Nx3 numpy array.
        RuntimeWarning: If no positive eigenvalues are found.
    """
    # Check if the input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The input must be a numpy array or a list.")

    # Check if the input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The input must be a 3xN or Nx3 numpy array.")

    # Force the array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Compute magnetic field calibration
    # Design matrix (S)
    s = np.concatenate(
        [
            np.square(magnetic_field[:, [0]]),
            magnetic_field[:, [0]] * magnetic_field[:, [1]],
            np.square(magnetic_field[:, [1]]),
            magnetic_field[:, [0]] * magnetic_field[:, [2]],
            magnetic_field[:, [1]] * magnetic_field[:, [2]],
            np.square(magnetic_field[:, [2]]),
            magnetic_field[:, :],
            np.ones((magnetic_field.shape[0], 1)),
        ],
        axis=1,
    )

    # Block Matrices: S_11, S_12, S_22
    sTs = s.T @ s
    s_11, s_12, s_22 = sTs[:3, :3], sTs[:3, 3:], sTs[3:, 3:]

    # Constrain matrix C_11
    c_11 = np.array([[0, 0, 2], [0, -1, 0], [2, 0, 0]])

    # Ellipsoid Parameters Estimation
    eigenvals, eigenvecs = np.linalg.eig(
        np.linalg.inv(c_11) @ (s_11 - s_12 @ np.linalg.inv(s_22) @ s_12.T)
    )

    if np.max(eigenvals) < 0:
        warnings.warn(
            "No positive eigenvalues: max eigenvalue = {:.6f}".format(
                np.max(eigenvals)
            ),
            RuntimeWarning,
        )

    a_1 = -eigenvecs[:, [np.argmax(eigenvals)]]
    a_2 = -np.linalg.inv(s_22) @ s_12.T @ a_1
    a = np.concatenate([a_1, a_2], axis=0).flatten()

    # Determine A and b
    a_matrix = np.array(
        [
            [a[0], a[1] / 2, a[3] / 2],
            [a[1] / 2, a[2], a[4] / 2],
            [a[3] / 2, a[4] / 2, a[5]],
        ]
    )
    hard_iron = np.linalg.inv(-2 * a_matrix) @ np.vstack(a[6:9])

    # Determine G and M
    u, s, vh = np.linalg.svd(a_matrix)
    g = u @ np.sqrt(np.diag(s)) @ vh
    soft_iron = np.linalg.inv(g)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    return hard_iron.flatten(), soft_iron, calibrated_magnetic_field

The full-magnetometer calibration least-squares problems can also be modeled as a factor graph. This can be implemented using the GTSAM python wrapper with the magFactor3 factor. This approach allows the user to get the soft-iron (SI) as the identity scaled by a constant and the hard-iron (HI) from the magnetometer bias.

This method assumes that the rotation from the body frame with respect to the world frame and the local magnetic field are known.

Parameters:

Name Type Description Default
magnetic_field Union[ndarray, list]

Magnetic field raw data

required
rph Union[ndarray, list]

Roll, pitch and heading data

required
magnetic_declination float

Magnetic declination in degrees

required
reference_magnetic_field Union[ndarray, list]

Reference magnetic field

required
optimizer str

Optimization algorithm to use. Options are "dogleg" or "lm" for the Dogleg and Levenberg-Marquardt optimizers respectively.

'dogleg'
relative_error_tol float

Relative error tolerance for the optimizer. Default is 1.00e-12

1e-12
absolute_error_tol float

Absolute error tolerance for the optimizer. Default is 1.00e-12

1e-12
max_iter int

Maximum number of iterations for the optimizer. Default is 1000

1000

Returns:

Name Type Description
hard_iron ndarray

Hard-iron offset in as a (3.) numpy array

soft_iron ndarray

Soft-iron scaling matrix

corrected_magnetic_field ndarray

Corrected magnetic field data

optimization_errors list

List of optimization errors in each iteration

Raises:

Type Description
TypeError

If the magnetic field input is not a numpy array or a list

TypeError

If the reference magnetic field input is not a numpy array or a list

TypeError

If the rph input is not a numpy array or a list

ValueError

If the magnetic field input is not a 3xN or Nx3 numpy array

ValueError

If the reference magnetic field input is not a 3, numpy array

ValueError

If the rph input is not a 3xN or Nx3 numpy array

TypeError

If the magnetic declination is not a float

ValueError

If the optimizer is not a string or not "dogleg" or "lm"

TypeError

If the relative error tolerance is not a float

TypeError

If the absolute error tolerance is not a float

ValueError

If the maximum number of iterations is not a positive integer

Source code in navlib/cal/cal_mag.py
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
def cal_mag_magfactor3(
    magnetic_field: Union[np.ndarray, list],
    rph: Union[np.ndarray, list],
    magnetic_declination: float,
    reference_magnetic_field: Union[np.ndarray, list],
    optimizer: str = "dogleg",
    relative_error_tol: float = 1.00e-12,
    absolute_error_tol: float = 1.00e-12,
    max_iter: int = 1000,
) -> Tuple[np.ndarray, np.ndarray, np.ndarray, list]:
    """
    The full-magnetometer calibration least-squares problems can also be modeled
    as a factor graph. This can be implemented using the [GTSAM](https://github.com/borglab/gtsam)
    python wrapper with the magFactor3 factor. This approach allows the user to get the soft-iron
    (SI) as the identity scaled by a constant and the hard-iron (HI) from the
    magnetometer bias.

    This method assumes that the rotation from the body frame with respect to
    the world frame and the local magnetic field are known.

    Args:
        magnetic_field (Union[np.ndarray, list]): Magnetic field raw data
        rph (Union[np.ndarray, list]): Roll, pitch and heading data
        magnetic_declination (float): Magnetic declination in degrees
        reference_magnetic_field (Union[np.ndarray, list]): Reference magnetic field
        optimizer (str): Optimization algorithm to use. Options are "dogleg" or "lm"
            for the Dogleg and Levenberg-Marquardt optimizers respectively.
        relative_error_tol (float): Relative error tolerance for the optimizer. Default is 1.00e-12
        absolute_error_tol (float): Absolute error tolerance for the optimizer. Default is 1.00e-12
        max_iter (int): Maximum number of iterations for the optimizer. Default is 1000

    Returns:
        hard_iron (np.ndarray): Hard-iron offset in as a (3.) numpy array
        soft_iron (np.ndarray): Soft-iron scaling matrix
        corrected_magnetic_field (np.ndarray): Corrected magnetic field data
        optimization_errors (list): List of optimization errors in each iteration

    Raises:
        TypeError: If the magnetic field input is not a numpy array or a list
        TypeError: If the reference magnetic field input is not a numpy array or a list
        TypeError: If the rph input is not a numpy array or a list
        ValueError: If the magnetic field input is not a 3xN or Nx3 numpy array
        ValueError: If the reference magnetic field input is not a 3, numpy array
        ValueError: If the rph input is not a 3xN or Nx3 numpy array
        TypeError: If the magnetic declination is not a float
        ValueError: If the optimizer is not a string or not "dogleg" or "lm"
        TypeError: If the relative error tolerance is not a float
        TypeError: If the absolute error tolerance is not a float
        ValueError: If the maximum number of iterations is not a positive integer
    """
    try:
        import gtsam
    except ImportError:
        raise ImportError(
            "gtsam is required for this calibration method. "
            "Install with: pip install navlib[calibration] (requires Python >= 3.12)."
        )

    # Check if the magnetic field input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the reference magnetic field input is a list and convert it to a numpy array
    if isinstance(reference_magnetic_field, list):
        reference_magnetic_field = np.array(reference_magnetic_field).flatten()

    # Check if the rph input is a list and convert it to a numpy array
    if isinstance(rph, list):
        rph = np.array(rph)

    # Check if the magnetic field input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field input must be a numpy array or a list.")

    # Check if the reference magnetic field input is a numpy array
    if not isinstance(reference_magnetic_field, np.ndarray):
        raise TypeError(
            "The reference magnetic field input must be a numpy array or a list."
        )

    # Check if the rph input is a numpy array
    if not isinstance(rph, np.ndarray):
        raise TypeError("The rph input must be a numpy array or a list.")

    # Check if the magnetic field input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field input must be a 3xN or Nx3 numpy array.")

    # Check if the reference magnetic field input is a 3, numpy array
    reference_magnetic_field = reference_magnetic_field.flatten()
    if reference_magnetic_field.shape[0] != 3:
        raise ValueError(
            "The reference magnetic field input must be a 3, or 1x3, or 3x1 numpy array."
        )

    # Check if the rph input is is a 3xN or Nx3 numpy array
    if rph.ndim != 2 or (rph.shape[0] != 3 and rph.shape[1] != 3):
        raise ValueError("The rph input must be a 3xN or Nx3 numpy array.")

    # Force the magnetic field array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Force the rph array to be a Nx3 numpy array
    if rph.shape[0] == 3:
        rph = rph.T

    # Check that the magnetic declination is a float
    if not isinstance(magnetic_declination, float):
        raise TypeError("The magnetic declination must be a float.")

    # Check that the optimizer is a string and is either "dogleg" or "lm"
    if not isinstance(optimizer, str) or optimizer not in ["dogleg", "lm"]:
        raise ValueError("The optimizer must be a string and either 'dogleg' or 'lm'.")

    # Check that the relative error tolerance is a float
    if not isinstance(relative_error_tol, float) or relative_error_tol <= 0:
        raise TypeError("The relative error tolerance must be a float.")

    # Check that the absolute error tolerance is a float
    if not isinstance(absolute_error_tol, float) or absolute_error_tol <= 0:
        raise TypeError("The absolute error tolerance must be a float.")

    # Check that the maximum number of iterations is a positive integer
    if not isinstance(max_iter, int) or max_iter <= 0:
        raise ValueError("The maximum number of iterations must be a positive integer.")

    # Compute attitude based on magnetic heading
    magnetic_hdg = ahrs_raw_hdg(magnetic_field, rph) - np.deg2rad(magnetic_declination)
    magnetic_rph = np.concatenate([rph[:, :2], magnetic_hdg.reshape(-1, 1)], axis=1)

    # Compute calibration
    # Smoothing and Mapping Factor Graph
    # 1. Create the non-linear graph
    graph = gtsam.NonlinearFactorGraph()

    # 2. noise model for each factor.
    residual_noise = gtsam.noiseModel.Isotropic.Sigma(3, 0.001)

    # 3. Creates values structure with initial values: S -> Scale, D -> Direction, B -> Bias
    initial = gtsam.Values()
    initial.insert(S(0), 1.0)
    initial.insert(B(0), gtsam.Point3(0, 0, 0))
    keys = [S(0), B(0)]

    # 4. Add factor for each measurement into a single node
    h0 = gtsam.Point3(reference_magnetic_field.flatten())

    for i in range(magnetic_field.shape[0]):
        mi = gtsam.Point3(magnetic_field[i, :])
        bRw = gtsam.Rot3(rph2rot(magnetic_rph[i, :]).T)

        # 5.1 magFactor3
        rf = gtsam.CustomFactor(
            residual_noise,
            keys,
            partial(_cal_mag_magfactor3_residual_factor, mi, h0, bRw),
        )
        graph.add(rf)

    # 5. If not online optimize the full batch
    # 5.1 Create optimizer parameters
    params = (
        gtsam.DoglegParams()
        if optimizer == "dogleg"
        else gtsam.LevenbergMarquardtParams()
    )
    params.setRelativeErrorTol(relative_error_tol)
    params.setAbsoluteErrorTol(absolute_error_tol)
    params.setMaxIterations(max_iter)
    params.setLinearSolverType("MULTIFRONTAL_CHOLESKY")

    # 5.2 Create optimizer
    if optimizer == "dogleg":
        optimizer = gtsam.DoglegOptimizer(graph, initial, params)
    else:
        optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)

    # 5.3 Optimize
    result, optimization_errors = _cal_mag_magfactor3_gtsam_optimize(optimizer, params)

    # 7. Process Results
    hard_iron = np.vstack(result.atPoint3(B(0)))
    soft_iron = result.atDouble(S(0)) * np.eye(3)

    # Correct the magnetic field
    corrected_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    corrected_magnetic_field = corrected_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    corrected_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ corrected_magnetic_field
    ).squeeze()

    return hard_iron.flatten(), soft_iron, corrected_magnetic_field, optimization_errors

Proposed method for the full calibration of a three-axis magnetometer using magnetic field and angular rate measurements. This particular approach is based on a factor graph processing all the data in a batch manner.

In particular MAGYC-BFG embeds the volume constraint for the soft-iron into a reparametrization for the Cholesky decomposition of the soft-iron matrix, allowing for the use of half the factors.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time stamps of the measurements.

required
measurements_window int

Window size for the measurements.

25
optimizer str

Optimization algorithm to use. Options are "dogleg" or "lm" for the Dogleg and Levenberg-Marquardt optimizers respectively.

'dogleg'
relative_error_tol float

Relative error tolerance for the optimizer. Default is 1.00e-07

1e-07
absolute_error_tol float

Absolute error tolerance for the optimizer. Default is 1.00e-07

1e-07
max_iter int

Maximum number of iterations for the optimizer. Default is 1000

1000

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

soft_iron ndarray

Estimated soft-iron matrix as a (3, 3) numpy array.

gyro_bias ndarray

Estimated gyroscope bias as a (3,) numpy array in rad/s.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

calibrated_angular_rate ndarray

Calibrated angular rate measurements in rad/s.

optimization_status Dict[str, Union[List[float], int]]

Dictionary with the optimization status. The keys are "error" and "iterations".

Raises:

Type Description
TypeError

If the magnetic field, angular rate, and time are not numpy arrays or lists.

ValueError

If the magnetic field and angular rate are not 3xN or Nx3 numpy arrays, or if the time is not a 1D numpy array.

ValueError

If the optimizer is not a string or not "dogleg" or "lm"

TypeError

If the relative error tolerance is not a float

TypeError

If the absolute error tolerance is not a float

ValueError

If the maximum number of iterations is not a positive integer

ValueError

If the measurements window is not a positive integer

Source code in navlib/cal/cal_mag.py
2230
2231
2232
2233
2234
2235
2236
2237
2238
2239
2240
2241
2242
2243
2244
2245
2246
2247
2248
2249
2250
2251
2252
2253
2254
2255
2256
2257
2258
2259
2260
2261
2262
2263
2264
2265
2266
2267
2268
2269
2270
2271
2272
2273
2274
2275
2276
2277
2278
2279
2280
2281
2282
2283
2284
2285
2286
2287
2288
2289
2290
2291
2292
2293
2294
2295
2296
2297
2298
2299
2300
2301
2302
2303
2304
2305
2306
2307
2308
2309
2310
2311
2312
2313
2314
2315
2316
2317
2318
2319
2320
2321
2322
2323
2324
2325
2326
2327
2328
2329
2330
2331
2332
2333
2334
2335
2336
2337
2338
2339
2340
2341
2342
2343
2344
2345
2346
2347
2348
2349
2350
2351
2352
2353
2354
2355
2356
2357
2358
2359
2360
2361
2362
2363
2364
2365
2366
2367
2368
2369
2370
2371
2372
2373
2374
2375
2376
2377
2378
2379
2380
2381
2382
2383
2384
2385
2386
2387
2388
2389
2390
2391
2392
2393
2394
2395
2396
2397
2398
2399
2400
2401
2402
2403
2404
2405
2406
2407
2408
2409
2410
2411
2412
2413
2414
2415
2416
2417
2418
2419
2420
2421
2422
2423
2424
2425
2426
2427
2428
2429
2430
2431
2432
2433
2434
2435
2436
2437
2438
2439
2440
2441
2442
2443
2444
2445
2446
2447
2448
2449
2450
2451
2452
2453
2454
2455
2456
2457
2458
2459
2460
2461
2462
2463
2464
2465
2466
2467
2468
2469
2470
2471
2472
2473
2474
2475
2476
2477
2478
2479
2480
2481
def cal_mag_magyc_bfg(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
    measurements_window: int = 25,
    optimizer: str = "dogleg",
    relative_error_tol: float = 1.00e-07,
    absolute_error_tol: float = 1.00e-07,
    max_iter: int = 1000,
) -> Tuple[
    np.ndarray,
    np.ndarray,
    np.ndarray,
    np.ndarray,
    np.ndarray,
    Dict[str, Union[List[float], int]],
]:
    """
    Proposed method for the full calibration of a three-axis magnetometer
    using magnetic field and angular rate measurements. This particular approach
    is based on a factor graph processing all the data in a batch manner.

    In particular MAGYC-BFG embeds the volume constraint for the soft-iron into
    a reparametrization for the Cholesky decomposition of the soft-iron matrix,
    allowing for the use of half the factors.


    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time stamps of the measurements.
        measurements_window (int): Window size for the measurements.
        optimizer (str): Optimization algorithm to use. Options are "dogleg" or "lm"
            for the Dogleg and Levenberg-Marquardt optimizers respectively.
        relative_error_tol (float): Relative error tolerance for the optimizer. Default is 1.00e-07
        absolute_error_tol (float): Absolute error tolerance for the optimizer. Default is 1.00e-07
        max_iter (int): Maximum number of iterations for the optimizer. Default is 1000

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Estimated soft-iron matrix as a (3, 3) numpy array.
        gyro_bias (numpy.ndarray): Estimated gyroscope bias as a (3,) numpy array in rad/s.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.
        calibrated_angular_rate (numpy.ndarray): Calibrated angular rate measurements in rad/s.
        optimization_status (Dict[str, Union[List[float], int]]): Dictionary with
            the optimization status. The keys are "error" and "iterations".

    Raises:
        TypeError: If the magnetic field, angular rate, and time are not numpy arrays or lists.
        ValueError: If the magnetic field and angular rate are not 3xN or Nx3 numpy
            arrays, or if the time is not a 1D numpy array.
        ValueError: If the optimizer is not a string or not "dogleg" or "lm"
        TypeError: If the relative error tolerance is not a float
        TypeError: If the absolute error tolerance is not a float
        ValueError: If the maximum number of iterations is not a positive integer
        ValueError: If the measurements window is not a positive integer
    """
    try:
        import gtsam
    except ImportError:
        raise ImportError(
            "gtsam is required for this calibration method. "
            "Install with: pip install navlib[calibration] (requires Python >= 3.12)."
        )

    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Check that the optimizer is a string and is either "dogleg" or "lm"
    if not isinstance(optimizer, str) or optimizer not in ["dogleg", "lm"]:
        raise ValueError("The optimizer must be a string and either 'dogleg' or 'lm'.")

    # Check that the relative error tolerance is a float
    if not isinstance(relative_error_tol, float) or relative_error_tol <= 0:
        raise TypeError("The relative error tolerance must be a float.")

    # Check that the absolute error tolerance is a float
    if not isinstance(absolute_error_tol, float) or absolute_error_tol <= 0:
        raise TypeError("The absolute error tolerance must be a float.")

    # Check that the maximum number of iterations is a positive integer
    if not isinstance(max_iter, int) or max_iter <= 0:
        raise ValueError("The maximum number of iterations must be a positive integer.")

    # Check that the measurements window is a positive integer
    if not isinstance(measurements_window, int) or measurements_window <= 0:
        raise ValueError("The measurements window must be a positive integer.")

    # Compute the magnetic field derivative
    magnetic_field_derivative = np.diff(magnetic_field, axis=0) / np.diff(time).reshape(
        -1, 1
    )
    magnetic_field_derivative = np.concatenate(
        [np.zeros((1, 3)), magnetic_field_derivative], axis=0
    )

    # Compute the magnetic calibration
    # Smoothing and Mapping Factor Graph
    # 1. Create the non-linear graph
    graph = gtsam.NonlinearFactorGraph()

    # 2. noise model for each factor.
    residual_noise = gtsam.noiseModel.Isotropic.Sigma(3, 1e-6)

    # 3. Creates values structure with initial values
    initial = gtsam.Values()
    initial.insert(S(0), np.array([0.0, 0.0, 0.0, 0.0, 0.0]))
    initial.insert(B(0), gtsam.Point3(0, 0, 0))
    initial.insert(W(0), gtsam.Point3(0, 0, 0))
    keys = [S(0), B(0), W(0)]

    # 4. Add factor for each measurement accumulates in the measurements window into a single node
    measurements_window = int(measurements_window)
    m_dot_window = np.empty((measurements_window, 3))
    m_window = np.empty((measurements_window, 3))
    w_window = np.empty((measurements_window, 3))

    # 5. Add factors to the graph
    for i in range(magnetic_field.shape[0]):
        # Get sensor measurements and estimated magnetic field derivative
        m_dot_window[i % measurements_window, :] = magnetic_field_derivative[i, :]
        m_window[i % measurements_window, :] = magnetic_field[i, :]
        w_window[i % measurements_window, :] = angular_rate[i, :]

        if i % measurements_window == 0 and i != 0:
            # Average measurements by the measurements window size.
            m_dot_meadian = np.median(m_dot_window, axis=0).reshape(3, 1)
            m_median = np.median(m_window, axis=0).reshape(3, 1)
            w_median = np.median(w_window, axis=0).reshape(3, 1)

            # 5.1 Residual factor
            rf = gtsam.CustomFactor(
                residual_noise,
                keys,
                partial(
                    _cal_mag_magyc_residual_factor, m_dot_meadian, m_median, w_median
                ),
            )
            graph.push_back(rf)

            # 5.2 Reset the measurements window
            m_dot_window = np.empty((measurements_window, 3))
            m_window = np.empty((measurements_window, 3))
            w_window = np.empty((measurements_window, 3))

    # 6. Optimize the graph
    # 6.1 Create optimizer parameters
    params = (
        gtsam.DoglegParams()
        if optimizer == "dogleg"
        else gtsam.LevenbergMarquardtParams()
    )
    params.setRelativeErrorTol(relative_error_tol)
    params.setAbsoluteErrorTol(absolute_error_tol)
    params.setMaxIterations(max_iter)
    params.setLinearSolverType("MULTIFRONTAL_CHOLESKY")

    # For dogleg method set the trust region. For good estimations, it ranges between 0.1 and 1.0
    if optimizer == "dogleg":
        params.setDeltaInitial(0.5)

    # 6.2 Create optimizer
    if optimizer == "dogleg":
        optimizer = gtsam.DoglegOptimizer(graph, initial, params)
    else:
        optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)

    # 6.3 Optimize
    result, optimization_status = _cal_mag_magyc_gtsam_optimize(optimizer, params)

    # 7. Process Results
    l_params = result.atVector(S(0))
    b = result.atVector(B(0))
    d = result.atVector(W(0))

    lower_triangular_matrix = np.array(
        [
            [exp(l_params[0]), 0, 0],
            [l_params[1], exp(l_params[2]), 0],
            [l_params[3], l_params[4], 1 / exp(l_params[0] + l_params[2])],
        ]
    )
    soft_iron = np.linalg.inv(lower_triangular_matrix @ lower_triangular_matrix.T)
    hard_iron = soft_iron @ np.vstack(b)
    gyro_bias = np.vstack(d)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    # Calibrated gyroscope measurements
    calibrated_angular_rate = angular_rate - gyro_bias.flatten()

    return (
        hard_iron.flatten(),
        soft_iron,
        gyro_bias.flatten(),
        calibrated_magnetic_field,
        calibrated_angular_rate,
        optimization_status,
    )

Proposed method for the full calibration of a three-axis magnetometer using magnetic field and angular rate measurements. This particular approach is based on a factor graph processing all the data in an incremental manner.

In particular MAGYC-IFG embeds the volume constraint for the soft-iron into a reparametrization for the Cholesky decomposition of the soft-iron matrix, allowing for the use of half the factors.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time stamps of the measurements.

required
measurements_window int

Window size for the measurements.

25

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

soft_iron ndarray

Estimated soft-iron matrix as a (3, 3) numpy array.

gyro_bias ndarray

Estimated gyroscope bias as a (3,) numpy array in rad/s.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

calibrated_angular_rate ndarray

Calibrated angular rate measurements in rad/s.

optimization_status Dict[str, ndarray]

Dictionary with the SI, HI and Wb for each iterations. The keys are: "soft_iron", "hard_iron", "gyro_bias", and "time".

Raises:

Type Description
TypeError

If the magnetic field, angular rate, and time are not numpy arrays or lists.

ValueError

If the magnetic field and angular rate are not 3xN or Nx3 numpy arrays, or if the time is not a 1D numpy array.

ValueError

If the measurements window is not a positive integer

Source code in navlib/cal/cal_mag.py
2484
2485
2486
2487
2488
2489
2490
2491
2492
2493
2494
2495
2496
2497
2498
2499
2500
2501
2502
2503
2504
2505
2506
2507
2508
2509
2510
2511
2512
2513
2514
2515
2516
2517
2518
2519
2520
2521
2522
2523
2524
2525
2526
2527
2528
2529
2530
2531
2532
2533
2534
2535
2536
2537
2538
2539
2540
2541
2542
2543
2544
2545
2546
2547
2548
2549
2550
2551
2552
2553
2554
2555
2556
2557
2558
2559
2560
2561
2562
2563
2564
2565
2566
2567
2568
2569
2570
2571
2572
2573
2574
2575
2576
2577
2578
2579
2580
2581
2582
2583
2584
2585
2586
2587
2588
2589
2590
2591
2592
2593
2594
2595
2596
2597
2598
2599
2600
2601
2602
2603
2604
2605
2606
2607
2608
2609
2610
2611
2612
2613
2614
2615
2616
2617
2618
2619
2620
2621
2622
2623
2624
2625
2626
2627
2628
2629
2630
2631
2632
2633
2634
2635
2636
2637
2638
2639
2640
2641
2642
2643
2644
2645
2646
2647
2648
2649
2650
2651
2652
2653
2654
2655
2656
2657
2658
2659
2660
2661
2662
2663
2664
2665
2666
2667
2668
2669
2670
2671
2672
2673
2674
2675
2676
2677
2678
2679
2680
2681
2682
2683
2684
2685
2686
2687
2688
2689
2690
2691
2692
2693
2694
2695
2696
2697
2698
2699
2700
2701
2702
2703
2704
2705
2706
2707
2708
2709
2710
2711
2712
2713
2714
2715
2716
2717
2718
2719
2720
2721
2722
2723
2724
2725
2726
2727
2728
2729
2730
2731
2732
2733
def cal_mag_magyc_ifg(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
    measurements_window: int = 25,
) -> Tuple[
    np.ndarray, np.ndarray, np.ndarray, np.ndarray, np.ndarray, Dict[str, np.ndarray]
]:
    """
    Proposed method for the full calibration of a three-axis magnetometer
    using magnetic field and angular rate measurements. This particular approach
    is based on a factor graph processing all the data in an incremental manner.

    In particular MAGYC-IFG embeds the volume constraint for the soft-iron into
    a reparametrization for the Cholesky decomposition of the soft-iron matrix,
    allowing for the use of half the factors.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time stamps of the measurements.
        measurements_window (int): Window size for the measurements.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Estimated soft-iron matrix as a (3, 3) numpy array.
        gyro_bias (numpy.ndarray): Estimated gyroscope bias as a (3,) numpy array in rad/s.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.
        calibrated_angular_rate (numpy.ndarray): Calibrated angular rate measurements in rad/s.
        optimization_status (Dict[str, np.ndarray]): Dictionary with the SI, HI
            and Wb for each iterations. The keys are: "soft_iron", "hard_iron",
            "gyro_bias", and "time".

    Raises:
        TypeError: If the magnetic field, angular rate, and time are not numpy arrays or lists.
        ValueError: If the magnetic field and angular rate are not 3xN or Nx3 numpy
            arrays, or if the time is not a 1D numpy array.
        ValueError: If the measurements window is not a positive integer
    """
    try:
        import gtsam
    except ImportError:
        raise ImportError(
            "gtsam is required for this calibration method. "
            "Install with: pip install navlib[calibration] (requires Python >= 3.12)."
        )

    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Check that the measurements window is a positive integer
    if not isinstance(measurements_window, int) or measurements_window <= 0:
        raise ValueError("The measurements window must be a positive integer.")

    # Compute the magnetic calibration
    # Smoothing and Mapping Factor Graph
    # 1. Create the non-linear graph
    graph = gtsam.NonlinearFactorGraph()

    # 2. Set iSAM2 parameters and create iSAM2 object
    isam_parameters = gtsam.ISAM2Params()
    dogleg_parameters = gtsam.ISAM2DoglegParams()
    dogleg_parameters.setInitialDelta(0.5)
    dogleg_parameters.setAdaptationMode("ONE_STEP_PER_ITERATION")
    isam_parameters.setOptimizationParams(dogleg_parameters)
    isam = gtsam.ISAM2(isam_parameters)

    # 3. noise model for each factor.
    residual_noise = gtsam.noiseModel.Isotropic.Sigma(3, 1e-6)

    # 4. Creates values structure with initial values
    initial = gtsam.Values()
    initial.insert(S(0), np.array([0.0, 0.0, 0.0, 0.0, 0.0]))
    initial.insert(B(0), gtsam.Point3(0, 0, 0))
    initial.insert(W(0), gtsam.Point3(0, 0, 0))
    keys = [S(0), B(0), W(0)]

    # Dictionary to save the progress of parameters during optimization
    optimization_status = {"S": [], "B": [], "W": [], "T": []}

    # 5. Add factor for each measurement accumulates in the measurements window into a single node
    measurements_window = int(measurements_window)
    m_window = np.empty((measurements_window, 3))
    w_window = np.empty((measurements_window, 3))
    t_window = np.empty((measurements_window,))

    # 6. Add factors to the graph
    for i in range(magnetic_field.shape[0]):
        # Get sensor measurements and estimated magnetic field derivative
        t_window[i % measurements_window] = time[i]
        m_window[i % measurements_window, :] = magnetic_field[i, :]
        w_window[i % measurements_window, :] = angular_rate[i, :]

        if i % measurements_window == 0 and i != 0:
            # Compute the derivative of the magnetic field for the window
            m_dot_window = np.diff(m_window, axis=0) / np.diff(t_window).reshape(-1, 1)

            # Average measurements by the measurements window size.
            m_dot_meadian = np.median(m_dot_window, axis=0).reshape(3, 1)
            m_median = np.median(m_window, axis=0).reshape(3, 1)
            w_median = np.median(w_window, axis=0).reshape(3, 1)

            # 6.1 Residual factor
            rf = gtsam.CustomFactor(
                residual_noise,
                keys,
                partial(
                    _cal_mag_magyc_residual_factor, m_dot_meadian, m_median, w_median
                ),
            )
            graph.push_back(rf)

            # 6.2 Perform incremental update to iSAM2's internal Bayes tree, optimizing only the affected variables.
            # Set iterations to start optimization, otherwise the optimizations starts as a ill-posed problem.
            # CHECK: If the measurement window is set to small values, the optimiaztion will raise RuntimeError
            # try:
            if (i // measurements_window) % 10 == 0:
                isam.update(graph, initial)
                current = isam.calculateEstimate()

                # Save the current parameters
                for key, variable in zip([S(0), B(0), W(0)], "SBW"):
                    vector = current.atVector(key).reshape(1, -1)
                    optimization_status[variable].append(vector)
                # Save the time as a unix timestamp in microseconds
                optimization_status["T"].append(int(datetime.now().timestamp() * 1e6))

                # except RuntimeError:
                #     warnings.warn("Skipping graph optimization due to indetermined system.")
                # finally:
                graph = gtsam.NonlinearFactorGraph()
                initial = gtsam.Values()

            # 6.5 Reset the measurements window
            t_window = np.empty((measurements_window,))
            m_window = np.empty((measurements_window, 3))
            w_window = np.empty((measurements_window, 3))

    # 7. Process Results
    # Update optimization status to have the actual matrices instead of the keys
    optimization_steps = len(optimization_status["S"])
    optimization_status_final = {
        "soft_iron": np.empty((optimization_steps, 9)),
        "hard_iron": np.empty((optimization_steps, 3)),
        "gyro_bias": np.empty((optimization_steps, 3)),
        "time": np.empty((optimization_steps,)),
    }

    for i in range(optimization_steps):
        # Get parameters
        l_params = optimization_status["S"][i].flatten()
        b = optimization_status["B"][i]
        d = optimization_status["W"][i]

        # Compute soft-iron, hard-iron and gyroscope bias
        lower_triangular_matrix = np.array(
            [
                [exp(l_params[0]), 0, 0],
                [l_params[1], exp(l_params[2]), 0],
                [l_params[3], l_params[4], 1 / exp(l_params[0] + l_params[2])],
            ]
        )
        soft_iron_i = np.linalg.inv(lower_triangular_matrix @ lower_triangular_matrix.T)
        hard_iron_i = soft_iron_i @ b.reshape(3, 1)
        gyro_bias_i = d.reshape(3, 1)

        # Fill the new optimization status dictionary
        optimization_status_final["soft_iron"][i, :] = soft_iron_i.flatten()
        optimization_status_final["hard_iron"][i, :] = hard_iron_i.flatten()
        optimization_status_final["gyro_bias"][i, :] = gyro_bias_i.flatten()
        optimization_status_final["time"][i] = optimization_status["T"][i]

    # Average the last 20% of the optimization steps to get the final calibration
    optimization_steps = int(0.2 * optimization_steps)
    soft_iron = np.mean(
        optimization_status_final["soft_iron"][-optimization_steps:], axis=0
    ).reshape(3, 3)
    hard_iron = np.mean(
        optimization_status_final["hard_iron"][-optimization_steps:], axis=0
    )
    gyro_bias = np.mean(
        optimization_status_final["gyro_bias"][-optimization_steps:], axis=0
    )

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    # Calibrated gyroscope measurements
    calibrated_angular_rate = angular_rate - gyro_bias.flatten()

    return (
        hard_iron.flatten(),
        soft_iron,
        gyro_bias.flatten(),
        calibrated_magnetic_field,
        calibrated_angular_rate,
        optimization_status_final,
    )

Proposed method for the full calibration of a three-axis magnetometer using magnetic field and angular rate measurements. This particular approach is based on a least squares optimization and poses the probems as a linear least squares optimization problem.

Even though a closed solution can be computed, it is an ill-conditioned problem and the optimization is preferred.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time stamps of the measurements.

required

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

soft_iron ndarray

Estimated soft-iron matrix as a (3, 3) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

Raises:

Type Description
TypeError

If the magnetic field, angular rate, and time are not numpy arrays or lists.

ValueError

If the magnetic field and angular rate are not 3xN or Nx3 numpy arrays, or if the time is not a 1D numpy array.

Source code in navlib/cal/cal_mag.py
1941
1942
1943
1944
1945
1946
1947
1948
1949
1950
1951
1952
1953
1954
1955
1956
1957
1958
1959
1960
1961
1962
1963
1964
1965
1966
1967
1968
1969
1970
1971
1972
1973
1974
1975
1976
1977
1978
1979
1980
1981
1982
1983
1984
1985
1986
1987
1988
1989
1990
1991
1992
1993
1994
1995
1996
1997
1998
1999
2000
2001
2002
2003
2004
2005
2006
2007
2008
2009
2010
2011
2012
2013
2014
2015
2016
2017
2018
2019
2020
2021
2022
2023
2024
2025
2026
2027
2028
2029
2030
2031
2032
2033
2034
2035
2036
2037
2038
2039
2040
2041
2042
2043
2044
2045
2046
2047
2048
2049
2050
2051
2052
2053
2054
2055
2056
2057
2058
2059
2060
2061
2062
2063
2064
2065
2066
2067
2068
2069
2070
2071
2072
2073
2074
2075
2076
def cal_mag_magyc_ls(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:
    """
    Proposed method for the full calibration of a three-axis magnetometer
    using magnetic field and angular rate measurements. This particular approach
    is based on a least squares optimization and poses the probems as a linear
    least squares optimization problem.

    Even though a closed solution can be computed, it is an ill-conditioned problem
    and the optimization is preferred.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time stamps of the measurements.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Estimated soft-iron matrix as a (3, 3) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.

    Raises:
        TypeError: If the magnetic field, angular rate, and time are not numpy arrays or lists.
        ValueError: If the magnetic field and angular rate are not 3xN or Nx3 numpy
            arrays, or if the time is not a 1D numpy array.
    """
    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Compute the skew symmetric matrix of the angular rate
    skew_symmetric_angular_rate = np.apply_along_axis(
        _cal_mag_magyc_vec_to_so3_jax, 1, angular_rate
    )

    # Compute the magnetic field derivative
    magnetic_field_derivative = np.diff(magnetic_field, axis=0) / np.diff(time).reshape(
        -1, 1
    )
    magnetic_field_derivative = np.concatenate(
        [np.zeros((1, 3)), magnetic_field_derivative], axis=0
    ).reshape(-1, 3, 1)

    # Reshape magnetic field
    magnetic_field_3d = magnetic_field.reshape(-1, 3, 1)

    # Compute the magnetic calibration
    # Least Squares Initial Guess and Constraints
    x0 = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])

    # Optimization
    res = least_squares(
        _cal_mag_magyc_ls_cost_function,
        x0,
        jac=_cal_mag_magyc_ls_jacobian,
        method="dogbox",
        verbose=0,
        loss="linear",
        max_nfev=1000,
        ftol=1.00e-06,
        gtol=None,
        xtol=None,
        x_scale="jac",
        args=(
            magnetic_field_3d,
            magnetic_field_derivative,
            skew_symmetric_angular_rate,
        ),
    )

    # Compute SI and HI
    x = res["x"]
    lower_triangular_matrix = np.array(
        [[exp(x[0]), 0, 0], [x[1], exp(x[2]), 0], [x[3], x[4], 1 / exp(x[0] + x[2])]]
    )
    soft_iron = np.linalg.inv(lower_triangular_matrix @ lower_triangular_matrix.T)
    hard_iron = soft_iron @ x[5:].reshape(3, 1)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    return hard_iron.flatten(), soft_iron, calibrated_magnetic_field

Proposed method for the full calibration of a three-axis magnetometer and a three-axis gyroscope using magnetic field and angular rate measurements. This particular approach is based on a least squares optimization and poses the probems as a non-linear least squares optimization problem.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time stamps of the measurements.

required

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

soft_iron ndarray

Estimated soft-iron matrix as a (3, 3) numpy array.

gyro_bias ndarray

Estimated gyroscope bias as a (3,) numpy array in rad/s.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

calibrated_angular_rate ndarray

Calibrated angular rate measurements in rad/s.

Raises:

Type Description
TypeError

If the magnetic field, angular rate, and time are not numpy arrays or lists.

ValueError

If the magnetic field and angular rate are not 3xN or Nx3 numpy arrays, or if the time is not a 1D numpy array.

Source code in navlib/cal/cal_mag.py
2079
2080
2081
2082
2083
2084
2085
2086
2087
2088
2089
2090
2091
2092
2093
2094
2095
2096
2097
2098
2099
2100
2101
2102
2103
2104
2105
2106
2107
2108
2109
2110
2111
2112
2113
2114
2115
2116
2117
2118
2119
2120
2121
2122
2123
2124
2125
2126
2127
2128
2129
2130
2131
2132
2133
2134
2135
2136
2137
2138
2139
2140
2141
2142
2143
2144
2145
2146
2147
2148
2149
2150
2151
2152
2153
2154
2155
2156
2157
2158
2159
2160
2161
2162
2163
2164
2165
2166
2167
2168
2169
2170
2171
2172
2173
2174
2175
2176
2177
2178
2179
2180
2181
2182
2183
2184
2185
2186
2187
2188
2189
2190
2191
2192
2193
2194
2195
2196
2197
2198
2199
2200
2201
2202
2203
2204
2205
2206
2207
2208
2209
2210
2211
2212
2213
2214
2215
2216
2217
2218
2219
2220
2221
2222
2223
2224
2225
2226
2227
def cal_mag_magyc_nls(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarray, np.ndarray]:
    """
    Proposed method for the full calibration of a three-axis magnetometer
    and a three-axis gyroscope using magnetic field and angular rate measurements.
    This particular approach is based on a least squares optimization and poses
    the probems as a non-linear least squares optimization problem.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time stamps of the measurements.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Estimated soft-iron matrix as a (3, 3) numpy array.
        gyro_bias (numpy.ndarray): Estimated gyroscope bias as a (3,) numpy array in rad/s.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.
        calibrated_angular_rate (numpy.ndarray): Calibrated angular rate measurements in rad/s.

    Raises:
        TypeError: If the magnetic field, angular rate, and time are not numpy arrays or lists.
        ValueError: If the magnetic field and angular rate are not 3xN or Nx3 numpy
            arrays, or if the time is not a 1D numpy array.
    """
    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Compute the skew symmetric matrix of the angular rate
    skew_symmetric_angular_rate = np.apply_along_axis(
        _cal_mag_magyc_vec_to_so3_jax, 1, angular_rate
    )

    # Compute the magnetic field derivative
    magnetic_field_derivative = np.diff(magnetic_field, axis=0) / np.diff(time).reshape(
        -1, 1
    )
    magnetic_field_derivative = np.vstack(
        [np.zeros((1, 3)), magnetic_field_derivative]
    ).reshape(-1, 3, 1)

    # Reshape magnetic field
    magnetic_field_3d = magnetic_field.reshape(-1, 3, 1)

    # Compute the magnetic calibration
    # Least Squares Initial Guess and Constraints
    x0 = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0])

    # Optimization
    res = least_squares(
        _cal_mag_magyc_nls_cost_function,
        x0,
        method="dogbox",
        jac=(
            _cal_mag_magyc_compute_jacobian_nls_jax
            if callable(_cal_mag_magyc_nls_jacobian)
            else "2-point"
        ),
        verbose=0,
        loss="linear",
        max_nfev=1000,
        ftol=1.00e-06,
        gtol=None,
        xtol=None,
        x_scale="jac",
        args=(
            magnetic_field_3d,
            magnetic_field_derivative,
            skew_symmetric_angular_rate,
        ),
    )

    # Compute SI, HI and Wb
    x = res["x"]
    lower_triangular_matrix = np.array(
        [[exp(x[0]), 0, 0], [x[1], exp(x[2]), 0], [x[3], x[4], 1 / exp(x[0] + x[2])]]
    )
    soft_iron = np.linalg.inv(lower_triangular_matrix @ lower_triangular_matrix.T)
    hard_iron = soft_iron @ x[5:8].reshape(3, 1)
    gyro_bias = x[8:].reshape(3, 1)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    # Calibrated gyroscope measurements
    calibrated_angular_rate = angular_rate - gyro_bias.flatten()

    return (
        hard_iron.flatten(),
        soft_iron,
        gyro_bias.flatten(),
        calibrated_magnetic_field,
        calibrated_angular_rate,
    )

The adaptive identification for sensor bias calibration proposes that the unknown sensor bias, \(b\), can be estimated on-line with a novel adaptive identification algorithm. The possible advantages of this adaptive approach are that (i) it does not require numerical differentiation of the sensor measurement \(x(t)\), (ii) it is less computationally expensive than the SAR-KF, and (iii) it could be combined with other nonlinear observer methods.

For further information refer to section IV.C in Troni, G. and Whitcomb, L. L. (2019). Field sensor bias calibration with angular-rate sensors: Theory and experimental evaluation with application to magnetometer calibration. IEEE/ASME Transactions on Mechatronics, 24(4):1698--1710.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time measurements in a 1D numpy array or list.

required
gains tuple

Gains defined in the set of equations (5) of the proposed method as a tuple of floats, by default (1.0, 1.0)

(1.0, 1.0)
f_normalize bool

Whether the k2 gain should be scaled by and adaptive constant computed as the reciprocal of the norm of the gyroscope measurement for that step, by default False.

False

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

calibrated_filtered_magnetic_field ndarray

Calibrated and filtered magnetic field measurements.

Raises:

Type Description
TypeError

If the magnetic field, angular rate, or time are not numpy arrays or lists.

ValueError

If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.

ValueError

If the magnetic field, angular rate, and time do not have the same number of samples.

TypeError

If the gains are not a tuple of floats.

TypeError

If the f_normalize is not a boolean.

Source code in navlib/cal/cal_mag.py
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
1678
1679
1680
1681
1682
1683
1684
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
1719
1720
1721
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
1735
1736
1737
1738
1739
1740
1741
1742
1743
1744
1745
1746
1747
1748
1749
1750
1751
1752
1753
1754
1755
1756
1757
1758
1759
1760
1761
1762
1763
1764
1765
1766
1767
def cal_mag_sar_aid(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
    gains: Tuple[float, float] = (1.0, 1.0),
    f_normalize: bool = False,
) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:
    """
    The adaptive identification for sensor bias calibration proposes that the
    unknown sensor bias, $b$, can be estimated on-line with a novel adaptive
    identification algorithm. The possible advantages of this adaptive approach
    are that (i) it does not require numerical differentiation of the sensor
    measurement $x(t)$, (ii) it is less computationally expensive than the SAR-KF,
    and (iii) it could be combined with other nonlinear observer methods.

    For further information refer to section IV.C in Troni, G. and Whitcomb, L. L.
    (2019). Field sensor bias calibration with angular-rate sensors: Theory and
    experimental evaluation with application to magnetometer calibration. IEEE/ASME
    Transactions on Mechatronics, 24(4):1698--1710.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time measurements in a 1D numpy array or list.
        gains (tuple): Gains defined in the set of equations (5) of the proposed method as
            a tuple of floats, by default (1.0, 1.0)
        f_normalize (bool): Whether the k2 gain should be scaled by and adaptive
            constant computed as the reciprocal of the norm of the gyroscope measurement
            for that step, by default False.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.
        calibrated_filtered_magnetic_field (numpy.ndarray): Calibrated and filtered magnetic field measurements.

    Raises:
        TypeError: If the magnetic field, angular rate, or time are not numpy arrays or lists.
        ValueError: If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.
        ValueError: If the magnetic field, angular rate, and time do not have the same number of samples.
        TypeError: If the gains are not a tuple of floats.
        TypeError: If the f_normalize is not a boolean.
    """
    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Check that the gains are a tuple of floats
    if not isinstance(gains, tuple):
        raise TypeError("The gains must be a tuple of floats.")
    if not all(isinstance(gain, float) for gain in gains):
        raise TypeError("The gains must be a tuple of floats.")

    # Check that the f_normalize is a boolean
    if not isinstance(f_normalize, bool):
        raise TypeError("The f_normalize must be a boolean.")

    # Compute the magnetic calibration
    # Initial parameters
    b0 = np.zeros((3,))
    k1 = gains[0]
    k2 = gains[1]
    mf = magnetic_field.reshape(3, -1)
    w = angular_rate.reshape(3, -1)
    dt = np.diff(time)
    dt_vec = np.concatenate([np.array([dt[0]]), dt])

    # Compute the skew-symmetric matrix of the angular rate.
    skew_symmetric_angular_rate = np.apply_along_axis(vec_to_so3, 1, angular_rate)

    # Adaptive ID system
    mh = np.zeros((3, mf.shape[1] + 1))
    mhd = np.zeros((3, mf.shape[1]))
    bh = np.zeros((3, mf.shape[1] + 1))
    bhd = np.zeros((3, mf.shape[1]))
    mh[:, 0] = magnetic_field[0, :]
    bh[:, 0] = b0

    for ix in range(mf.shape[1]):
        mhd[:, ix] = (
            -skew_symmetric_angular_rate[ix, :, :] @ mh[:, ix]
            + skew_symmetric_angular_rate[ix, :, :] @ bh[:, ix]
            - k1 * (mh[:, ix] - mf[:, ix])
        )

        if (np.linalg.norm(w[:, ix]) > 0.01) and f_normalize:
            k_adap = 1 / np.linalg.norm(w[:, ix])
            bhd[:, ix] = (
                -k_adap
                * k2
                * skew_symmetric_angular_rate[ix, :, :]
                @ (mh[:, ix] - mf[:, ix])
            )
        else:
            bhd[:, ix] = (
                -k2 * skew_symmetric_angular_rate[ix, :, :].T @ (mh[:, ix] - mf[:, ix])
            )

        mh[:, ix + 1] = mh[:, ix] + dt_vec[ix] * mhd[:, ix]
        bh[:, ix + 1] = bh[:, ix] + dt_vec[ix] * bhd[:, ix]

    # Final Bias averaging last 20%
    hard_iron = np.mean(
        bh[:, -int(np.round(mf.shape[1] * 0.2)) :], axis=1, keepdims=True
    )

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field - hard_iron.flatten()
    calibrated_filtered_magnetic_field = mh[:, :-1].T

    return (
        hard_iron.flatten(),
        calibrated_magnetic_field,
        calibrated_filtered_magnetic_field,
    )

The Kalman filter for sensor bias calibration uses the system model with a discretization of the continuous-time system the sensor bias estimation can be solved with a standard discrete-time Kalman filter implementation that does not require differentiation.

\[\dot{x}_i = -\omega_i \times (x_i - b)\]

Where \(x(t)\) is the measured magnetic field, \(\dot{x(t)}\) is the measured magnetic field differentiated with respect to time, \(\omega(t)\) is the measured angular-rate in instrument coordinates, and \(b\) is the hard-iron.

For further information refer to section IV.B in Troni, G. and Whitcomb, L. L. (2019). Field sensor bias calibration with angular-rate sensors: Theory and experimental evaluation with application to magnetometer calibration. IEEE/ASME Transactions on Mechatronics, 24(4):1698--1710.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time measurements in a 1D numpy array or list.

required
gains tuple

Kalman filter gains.

(1.0, 1.0)
f_normalize bool

Whether the k2 gain should be scaled by and adaptive constant computed as the reciprocal of the norm of the gyroscope measurement for that step, by default False.

False

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

calibrated_filtered_magnetic_field ndarray

Calibrated and filtered magnetic field measurements.

Raises:

Type Description
TypeError

If the magnetic field, angular rate, or time are not numpy arrays or lists.

ValueError

If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.

ValueError

If the magnetic field, angular rate, and time do not have the same number of samples.

TypeError

If the gains are not a tuple of floats.

TypeError

If the f_normalize is not a boolean.

Source code in navlib/cal/cal_mag.py
1433
1434
1435
1436
1437
1438
1439
1440
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
1459
1460
1461
1462
1463
1464
1465
1466
1467
1468
1469
1470
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
1481
1482
1483
1484
1485
1486
1487
1488
1489
1490
1491
1492
1493
1494
1495
1496
1497
1498
1499
1500
1501
1502
1503
1504
1505
1506
1507
1508
1509
1510
1511
1512
1513
1514
1515
1516
1517
1518
1519
1520
1521
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
1535
1536
1537
1538
1539
1540
1541
1542
1543
1544
1545
1546
1547
1548
1549
1550
1551
1552
1553
1554
1555
1556
1557
1558
1559
1560
1561
1562
1563
1564
1565
1566
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
1605
1606
1607
def cal_mag_sar_kf(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
    gains: Tuple[float, float] = (1.0, 1.0),
    f_normalize: bool = False,
) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:
    """
    The Kalman filter for sensor bias calibration uses the system model with  a
    discretization of the continuous-time system the sensor bias estimation can
    be solved with a standard discrete-time Kalman filter implementation that
    does not require differentiation.

    $$\\dot{x}_i = -\\omega_i \\times (x_i - b)$$

    Where $x(t)$ is the measured magnetic field, $\\dot{x(t)}$ is the measured
    magnetic field differentiated with respect to time, $\\omega(t)$ is the
    measured angular-rate in instrument coordinates, and $b$ is the hard-iron.

    For further information refer to section IV.B in Troni, G. and Whitcomb, L. L.
    (2019). Field sensor bias calibration with angular-rate sensors: Theory and
    experimental evaluation with application to magnetometer calibration. IEEE/ASME
    Transactions on Mechatronics, 24(4):1698--1710.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time measurements in a 1D numpy array or list.
        gains (tuple): Kalman filter gains.
        f_normalize (bool): Whether the k2 gain should be scaled by and adaptive
            constant computed as the reciprocal of the norm of the gyroscope measurement
            for that step, by default False.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.
        calibrated_filtered_magnetic_field (numpy.ndarray): Calibrated and filtered magnetic field measurements.

    Raises:
        TypeError: If the magnetic field, angular rate, or time are not numpy arrays or lists.
        ValueError: If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.
        ValueError: If the magnetic field, angular rate, and time do not have the same number of samples.
        TypeError: If the gains are not a tuple of floats.
        TypeError: If the f_normalize is not a boolean.
    """
    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Check that the gains are a tuple of floats
    if not isinstance(gains, tuple):
        raise TypeError("The gains must be a tuple of floats.")
    if not all(isinstance(gain, float) for gain in gains):
        raise TypeError("The gains must be a tuple of floats.")

    # Check that the f_normalize is a boolean
    if not isinstance(f_normalize, bool):
        raise TypeError("The f_normalize must be a boolean.")

    # Compute the magnetic calibration
    # Initial parameters
    b0 = np.zeros((3,))
    k1a = gains[0]
    k1b = gains[1] if len(gains) >= 2 else gains[0]
    k2 = gains[2] if len(gains) >= 3 else gains[1]
    mf = magnetic_field.reshape(3, -1)
    w = angular_rate.reshape(3, -1)
    dt = np.diff(time)
    dt_vec = np.concatenate([np.array([dt[0]]), dt])

    # Kalman Model
    Bc = np.zeros([6, 1])
    # Measurement model
    H1 = np.hstack([np.eye(3), np.zeros([3, 3])])
    # Process noise covariance
    Qc = np.diag([k1a, k1a, k1a, k1b, k1b, k1b])
    # Variance in the measurements
    R = np.diag([k2, k2, k2])

    # KF
    F1 = _cal_mag_sar_kf_transition_matrix([0, 0, 0])
    n = F1.shape[0]
    m = F1.shape[1]
    MM = np.zeros([n, mf.shape[1]])
    PP = np.zeros([n, m, mf.shape[1]])
    AA = np.zeros([n, m, mf.shape[1]])
    QQ = np.zeros([n, m, mf.shape[1]])
    KK = np.zeros([n, H1.shape[0], mf.shape[1]])

    # Initial guesses for the state mean and covariance.
    x = np.hstack([mf[:, 0], b0])
    p01 = 0.001  # P0 gyro
    p02 = 0.001  # P0 bias
    P0 = np.diag([p01, p01, p01, p02, p02, p02])
    P = P0

    # Filtering steps.
    for ix in range(mf.shape[1]):
        # Discretization of the continous-time system (dtk)
        dtk = dt_vec[ix]
        u = w[:, ix]

        [Ak, Bk, Qk] = _cal_mag_sar_kf_lti_discretize(
            _cal_mag_sar_kf_transition_matrix(u), Bc, Qc, dtk
        )

        AA[:, :, ix] = Ak
        QQ[:, :, ix] = Qk

        # Prediction
        [x, P] = _cal_mag_sar_kf_predict(x, P, Ak, Qk)
        [x, P, K, dy, S] = _cal_mag_sar_kf_update(x, P, mf[:, ix], H1, R)

        MM[:, ix] = x
        PP[:, :, ix] = P
        KK[:, :, ix] = K

    # Final Bias averaging last 20%
    hard_iron = np.mean(
        MM[3:, -int(np.round(mf.shape[1] * 0.2)) :], axis=1, keepdims=True
    )

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field - hard_iron.flatten()
    calibrated_filtered_magnetic_field = MM[:3, :].T

    return (
        hard_iron.flatten(),
        calibrated_magnetic_field,
        calibrated_filtered_magnetic_field,
    )

The linear least squares for sensor bias calibration is seeks to minimize the sum of squared residuals

\[\sum_{i=1}^{n} \frac{1}{\sigma_i^2} ||\dot{x}_i + \omega_i \times (x_i - b)||^2\]

Where \(x(t)\) is the measured magnetic field, \(\dot{x(t)}\) is the measured magnetic field differentiated with respect to time, \(\omega(t)\) is the measured angular-rate in instrument coordinates, \(b\) is the hard-iron, and \(\times\) is the standard cross product operator.

This optimization problem can be solved in an analytical way. For further information refer to section IV.A in Troni, G. and Whitcomb, L. L. (2019). Field sensor bias calibration with angular-rate sensors: Theory and experimental evaluation with application to magnetometer calibration. IEEE/ASME Transactions on Mechatronics, 24(4):1698--1710.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
angular_rate ndarray or list

Angular rate measurements in a 3xN or Nx3 numpy array or list.

required
time ndarray or list

Time measurements in a 1D numpy array or list.

required

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements.

Raises:

Type Description
TypeError

If the magnetic field, angular rate, or time are not numpy arrays or lists.

ValueError

If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.

ValueError

If the magnetic field, angular rate, and time do not have the same number of samples.

Source code in navlib/cal/cal_mag.py
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
1421
1422
1423
1424
1425
1426
1427
1428
1429
1430
def cal_mag_sar_ls(
    magnetic_field: Union[np.ndarray, list],
    angular_rate: Union[np.ndarray, list],
    time: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray]:
    """
    The linear least squares for sensor bias calibration is seeks to minimize the
    sum of squared residuals

    $$\\sum_{i=1}^{n} \\frac{1}{\\sigma_i^2} ||\\dot{x}_i + \\omega_i \\times (x_i - b)||^2$$

    Where $x(t)$ is the measured magnetic field, $\\dot{x(t)}$ is the measured
    magnetic field differentiated with respect to time, $\\omega(t)$ is the
    measured angular-rate in instrument coordinates, $b$ is the hard-iron, and
    $\\times$ is the standard cross product operator.

    This optimization problem can be solved in an analytical way. For further
    information refer to section IV.A in Troni, G. and Whitcomb, L. L. (2019).
    Field sensor bias calibration with angular-rate sensors: Theory and experimental
    evaluation with application to magnetometer calibration. IEEE/ASME Transactions
    on Mechatronics, 24(4):1698--1710.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        angular_rate (numpy.ndarray or list): Angular rate measurements in a 3xN or
            Nx3 numpy array or list.
        time (numpy.ndarray or list): Time measurements in a 1D numpy array or list.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements.

    Raises:
        TypeError: If the magnetic field, angular rate, or time are not numpy arrays or lists.
        ValueError: If the magnetic field, angular rate, or time are not 3xN or Nx3 numpy arrays.
        ValueError: If the magnetic field, angular rate, and time do not have the same number of samples.
    """
    # Check if the magnetic_field, angular_rate, and time are lists and convert them to numpy arrays
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)
    if isinstance(angular_rate, list):
        angular_rate = np.array(angular_rate)
    if isinstance(time, list):
        time = np.array(time)

    # Check if the magnetic_field, angular_rate, and time are numpy arrays
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field must be a numpy array or a list.")
    if not isinstance(angular_rate, np.ndarray):
        raise TypeError("The angular rate must be a numpy array or a list.")
    if not isinstance(time, np.ndarray):
        raise TypeError("The time must be a numpy array or a list.")

    # Check if the magnetic_field and angular_rate are 3xN or Nx3 numpy arrays
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field must be a 3xN or Nx3 numpy array.")
    if angular_rate.ndim != 2 or (
        angular_rate.shape[0] != 3 and angular_rate.shape[1] != 3
    ):
        raise ValueError("The angular rate must be a 3xN or Nx3 numpy array.")

    # Check if the time is a 1D numpy array
    time = time.flatten()
    if time.ndim != 1:
        raise ValueError("The time must be a (n, ), (n, 1) or (1, n) numpy array.")

    # Force the magnetic_field and angular_rate to be Nx3 numpy arrays
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T
    if angular_rate.shape[0] == 3:
        angular_rate = angular_rate.T

    # Check if the magnetic_field, angular_rate, and time have the same number of samples
    if (
        magnetic_field.shape[0] != angular_rate.shape[0]
        or magnetic_field.shape[0] != time.shape[0]
    ):
        raise ValueError(
            "The magnetic field, angular rate, and time must have the same number of samples."
        )

    # Compute the magnetic calibration
    # Get the data variance
    magnetic_field_variance = _cal_mag_sar_ls_get_sigma_noise(magnetic_field)
    sigma_i = np.linalg.norm(magnetic_field_variance).reshape(-1, 1, 1)

    # Compute the skew-symmetric matrix of the angular rate.
    skew_symmetric_angular_rate = np.apply_along_axis(vec_to_so3, 1, angular_rate)

    # Compute the magnetic field derivative
    magnetic_field_derivative = np.diff(magnetic_field, axis=0) / np.diff(time).reshape(
        -1, 1
    )
    magnetic_field_derivative = np.concatenate(
        [np.zeros((1, 3)), magnetic_field_derivative], axis=0
    )

    # Estimate b
    b1_inv = np.linalg.inv(
        np.einsum("ijk->jk", (skew_symmetric_angular_rate**2) * (1 / sigma_i))
    )

    yi = np.einsum(
        "ijk->ikj",
        np.cross(angular_rate.reshape(-1, 1, 3), magnetic_field.reshape(-1, 1, 3))
        + magnetic_field_derivative.reshape(-1, 1, 3),
    )
    b2 = np.einsum("ijk->jk", (skew_symmetric_angular_rate @ yi) * (1 / sigma_i))

    hard_iron = b1_inv @ b2

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field - hard_iron.flatten()

    return hard_iron.flatten(), calibrated_magnetic_field

The sphere fit method fits a sphere to a collection of data using a closed form for the solution. With this purpose, propose an optimization problem that seeks to minimize the sum:

\[\sum_i ((x_i-x_c)^2+(y_i-y_c)^2+(z_i-z_c)^2-r^2)^2\]

Where x, y, and z is the data; \(x_c\), \(y_c\), and \(z_c\) are the sphere center; and r is the radius.

The method assumes that points are not in a singular configuration and are real numbers to solve this problem. If you have coplanar data, use a circle fit with svd for determining the plane, recommended Circle Fit (Pratt method), by Nikolai Chernov

Inspired by Alan Jennings, University of Dayton, implementation (source)

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required

Returns:

Name Type Description
hard_iron ndarray

Hard iron bias as a (3,) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field measurements

Raises:

Type Description
TypeError

If the input is not a numpy array or a list.

ValueError

If the input is not a 3xN or Nx3 numpy array.

Source code in navlib/cal/cal_mag.py
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
def cal_mag_sphere_fit(
    magnetic_field: Union[np.ndarray, list],
) -> Tuple[np.ndarray, np.ndarray]:
    """
    The sphere fit method fits a sphere to a collection of data using a closed
    form for the solution. With this purpose, propose an optimization problem that
    seeks to minimize the sum:

    $$\\sum_i ((x_i-x_c)^2+(y_i-y_c)^2+(z_i-z_c)^2-r^2)^2$$

    Where x, y, and z is the data; $x_c$, $y_c$, and $z_c$ are the sphere center;
    and r is the radius.

    The method assumes that points are not in a singular configuration and are
    real numbers to solve this problem. If you have coplanar data, use a circle
    fit with svd for determining the plane, recommended [Circle Fit (Pratt method),
    by Nikolai Chernov](http://www.mathworks.com/matlabcentral/fileexchange/22643)

    Inspired by Alan Jennings, University of Dayton, implementation ([source](
    https://www.mathworks.com/matlabcentral/fileexchange/34129-sphere-fit-least-squared))

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.

    Returns:
        hard_iron (numpy.ndarray): Hard iron bias as a (3,) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field measurements

    Raises:
        TypeError: If the input is not a numpy array or a list.
        ValueError: If the input is not a 3xN or Nx3 numpy array.
    """
    # Check if the input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The input must be a numpy array or a list.")

    # Check if the input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The input must be a 3xN or Nx3 numpy array.")

    # Force the array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Compute magnetic field calibration
    mf = magnetic_field
    a_matrix = np.array(
        [
            [
                np.mean(mf[:, 0] * (mf[:, 0] - np.mean(mf[:, 0]))),
                2 * np.mean(mf[:, 0] * (mf[:, 1] - np.mean(mf[:, 1]))),
                2 * np.mean(mf[:, 0] * (mf[:, 2] - np.mean(mf[:, 2]))),
            ],
            [
                0,
                np.mean(mf[:, 1] * (mf[:, 1] - np.mean(mf[:, 1]))),
                2 * np.mean(mf[:, 1] * (mf[:, 2] - np.mean(mf[:, 2]))),
            ],
            [0, 0, np.mean(mf[:, 2] * (mf[:, 2] - np.mean(mf[:, 2])))],
        ]
    )

    a_matrix = a_matrix + a_matrix.T
    b_matrix = np.array(
        [
            [
                np.mean(
                    (mf[:, 0] ** 2 + mf[:, 1] ** 2 + mf[:, 2] ** 2)
                    * (mf[:, 0] - np.mean(mf[:, 0]))
                )
            ],
            [
                np.mean(
                    (mf[:, 0] ** 2 + mf[:, 1] ** 2 + mf[:, 2] ** 2)
                    * (mf[:, 1] - np.mean(mf[:, 1]))
                )
            ],
            [
                np.mean(
                    (mf[:, 0] ** 2 + mf[:, 1] ** 2 + mf[:, 2] ** 2)
                    * (mf[:, 2] - np.mean(mf[:, 2]))
                )
            ],
        ]
    )

    hard_iron = np.array(np.linalg.lstsq(a_matrix, b_matrix, rcond=None)[0])

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field - hard_iron.flatten()

    return hard_iron.flatten(), calibrated_magnetic_field

The TWOSTEP method proposes a fast, robust algorithm for estimating magnetometer biases when the attitude is unknown. This algorithm combines the convergence in a single step of a heuristic algorithm currently in use with the correct treatment of the statistics of the measurements and does without discarding data.

This algorithm was the in a first publication developed for the estimation of the hard-iron (Alonso, R. Shuster, M.D. (2002a). TWOSTEP: A fast, robust algorithm for attitude-independent magnetometer-bias determination. Journal of the Astronautical Sciences, 50(4):433-452.

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
reference_magnetic_field ndarray or list

Reference magnetic field measurements in a 3, or 1x3, or 3x1 numpy array or list.

required
max_iterations int

Maximum number of iterations for the second step.

2000
measurement_noise_std float

Standard deviation that characterizes the measurements' noise, by default 0.001 G.

0.001

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field as a 3xN numpy array.

Raises:

Type Description
TypeError

If the magnetic field or reference magnetic field inputs are not numpy arrays or lists.

ValueError

If the magnetic field input is not a 3xN or Nx3 numpy array, if the reference magnetic field input is not a 3, or 1x3, or 3x1 numpy array, if the maximum number of iterations is not a positive integer, or if the measurement noise standard deviation is not a positive float.

Source code in navlib/cal/cal_mag.py
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
def cal_mag_twostep_hi(
    magnetic_field: Union[np.ndarray, list],
    reference_magnetic_field: Union[np.ndarray, list],
    max_iterations: int = 2000,
    measurement_noise_std: float = 1e-3,
) -> Tuple[np.ndarray, np.ndarray]:
    """
    The TWOSTEP method proposes a fast, robust algorithm for estimating magnetometer
    biases when the attitude is unknown. This algorithm combines the convergence
    in a single step of a heuristic algorithm currently in use with the correct
    treatment of the statistics of the measurements and does without discarding
    data.

    This algorithm was the in a first publication developed for the estimation of
    the hard-iron (Alonso, R. Shuster, M.D. (2002a). TWOSTEP: A fast, robust
    algorithm for attitude-independent magnetometer-bias determination. Journal
    of the Astronautical Sciences, 50(4):433-452.

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        reference_magnetic_field (numpy.ndarray or list): Reference magnetic field
            measurements in a 3, or 1x3, or 3x1 numpy array or list.
        max_iterations (int): Maximum number of iterations for the second step.
        measurement_noise_std (float): Standard deviation that characterizes the
            measurements' noise, by default 0.001 G.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field as a
                3xN numpy array.

    Raises:
        TypeError: If the magnetic field or reference magnetic field inputs are not
            numpy arrays or lists.
        ValueError: If the magnetic field input is not a 3xN or Nx3 numpy array, if
            the reference magnetic field input is not a 3, or 1x3, or 3x1 numpy array,
            if the maximum number of iterations is not a positive integer, or if the
            measurement noise standard deviation is not a positive float.
    """
    # Check if the magnetic field input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the reference magnetic field input is a list and convert it to a numpy array
    if isinstance(reference_magnetic_field, list):
        reference_magnetic_field = np.array(reference_magnetic_field).flatten()

    # Check if the magnetic field input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field input must be a numpy array or a list.")

    # Check if the reference magnetic field input is a numpy array
    if not isinstance(reference_magnetic_field, np.ndarray):
        raise TypeError(
            "The reference magnetic field input must be a numpy array or a list."
        )

    # Check if the magnetic field input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field input must be a 3xN or Nx3 numpy array.")

    # Check if the reference magnetic field input is a 3, numpy array
    if reference_magnetic_field.ndim != 1 and reference_magnetic_field.size != 3:
        raise ValueError(
            "The reference magnetic field input must be a 3, or 1x3, or 3x1 numpy array."
        )

    # Force the magnetic field array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Check that the maximum number of iterations is a positive integer
    if not isinstance(max_iterations, int) or max_iterations <= 0:
        raise ValueError("The maximum number of iterations must be a positive integer.")

    # Check that the measurement noise standard deviation is a positive float
    if not isinstance(measurement_noise_std, float) or measurement_noise_std <= 0:
        raise ValueError(
            "The measurement noise standard deviation must be a positive float."
        )

    # Compute magnetic field calibration
    mf = magnetic_field

    # First step
    b0 = np.zeros((3, 1))

    # Effective measurement from paper equation (3a)
    b_matrix = np.ones((mf.shape)) * reference_magnetic_field
    z_k = (
        np.square(np.linalg.norm(mf, axis=1))
        - np.square(np.linalg.norm(b_matrix, axis=1))
    ).reshape(-1, 1)

    # Sensor measurements noise modeled as white gaussian with standard deviation epsilon_k
    epsilon_sq_k = np.ones(mf.shape) * (measurement_noise_std**2)

    # Sensor error scalar measurement noise characterization as gaussian.
    # Gaussian distribution mean, equation (7a)
    mu_k = -np.sum(epsilon_sq_k, axis=1, keepdims=True)

    # Gaussian distribution variance, equation (5.15)
    sigma_sq_k = (
        4
        * (
            (mf.reshape(-1, 1, 3) - b0.reshape(1, 3))
            @ np.apply_along_axis(np.diag, 1, epsilon_sq_k)
            @ (mf.reshape(-1, 3, 1) - b0)
        )
        + 2
        * np.apply_along_axis(
            lambda x: np.square(np.trace(np.diag(x))), 1, epsilon_sq_k
        ).reshape(-1, 1, 1)
    ).reshape(-1, 1)

    # Calculate  centered sigma squared, equation (14)
    sigma_sq_bar = 1 / np.sum(1 / sigma_sq_k)

    # Center  the  data
    mu_bar, mu_k_tilde = _cal_mag_twostep_center_data(mu_k, sigma_sq_k, sigma_sq_bar)
    z_bar, z_k_tilde = _cal_mag_twostep_center_data(z_k, sigma_sq_k, sigma_sq_bar)
    b_bar, b_k_tilde = _cal_mag_twostep_center_data(b_matrix, sigma_sq_k, sigma_sq_bar)

    # Offset and error covariance matrix calculation from paper equations (33) and (34)
    F_bb_tilde = np.einsum(
        "ijk->jk",
        (4 / sigma_sq_k.reshape(-1, 1, 1))
        * (b_k_tilde.reshape(-1, 3, 1) @ b_k_tilde.reshape(-1, 1, 3)),
    )
    F_zb = np.einsum(
        "ijk->jk",
        ((z_k_tilde - mu_k_tilde) * (2 / sigma_sq_k)).reshape(-1, 1, 1)
        * b_k_tilde.reshape(-1, 3, 1),
    )
    b = np.linalg.inv(F_bb_tilde) @ F_zb

    # Second Step: Iterative
    F_bb_bar = (
        (4 / sigma_sq_bar) * (b_bar.reshape(-1, 1) - b) @ (b_bar.reshape(-1, 1) - b).T
    )
    b_asterisk = np.copy(b)

    if np.max(np.diag(F_bb_bar) / np.diag(F_bb_tilde)) > 0.001:
        F_bb = F_bb_tilde + F_bb_bar
        gg = (F_bb_tilde @ (b - b_asterisk)) - (1 / sigma_sq_bar) * (
            z_bar - 2 * (b_bar @ b) + np.linalg.norm(b) ** 2 - mu_bar
        ) * 2 * (b_bar.reshape(-1, 1) - b)
        bn = b - np.linalg.inv(F_bb) @ gg

        iter = 1
        while ((bn - b).T @ F_bb @ (bn - b)) > 0.001:
            b = np.copy(bn)
            gg = (F_bb_tilde @ (b - b_asterisk)) - (1 / sigma_sq_bar) * (
                z_bar - 2 * (b_bar @ b) + np.linalg.norm(b) ** 2 - mu_bar
            ) * 2 * (b_bar.reshape(-1, 1) - b)
            F_bb_bar = (
                (4 / sigma_sq_bar)
                * (b_bar.reshape(-1, 1) - b)
                @ (b_bar.reshape(-1, 1) - b).T
            )
            F_bb = F_bb_tilde + F_bb_bar
            bn = b - np.linalg.inv(F_bb) @ gg

            iter += 1
            if iter > max_iterations:
                warnings.warn(
                    "Second step: Maximum number of iterations reached.", RuntimeWarning
                )
                break

    hard_iron = bn.reshape(3, 1)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field - hard_iron.flatten()

    return hard_iron.flatten(), calibrated_magnetic_field

The TWOSTEP method proposes a fast, robust algorithm for estimating magnetometer biases when the attitude is unknown. This algorithm combines the convergence in a single step of a heuristic algorithm currently in use with the correct treatment of the statistics of the measurements and does without discarding data.

This algorithm was extended in a second iteration to compute also the soft-iron (Alonso, R. Shuster, M.D. (2002b). Complete linear attitude-independent magnetometer calibration. Journal of the Astronautical Science, 50(4):477-490).

Parameters:

Name Type Description Default
magnetic_field ndarray or list

Magnetic field measurements in a 3xN or Nx3 numpy array or list.

required
reference_magnetic_field ndarray or list

Reference magnetic field measurements in a 3, or 1x3, or 3x1 numpy array or list.

required
max_iterations int

Maximum number of iterations for the second step.

2000
measurement_noise_std float

Standard deviation that characterizes the measurements' noise, by default 0.001 G.

0.001

Returns:

Name Type Description
hard_iron ndarray

Estimated hard-iron bias as a (3,) numpy array.

soft_iron ndarray

Estimated soft-iron matrix as a (3,3) numpy array.

calibrated_magnetic_field ndarray

Calibrated magnetic field as a 3xN numpy array.

Raises:

Type Description
TypeError

If the magnetic field or reference magnetic field inputs are not numpy arrays or lists.

ValueError

If the magnetic field input is not a 3xN or Nx3 numpy array, if the reference magnetic field input is not a 3, or 1x3, or 3x1 numpy array, if the maximum number of iterations is not a positive integer, or if the measurement noise standard deviation is not a positive float.

Source code in navlib/cal/cal_mag.py
 793
 794
 795
 796
 797
 798
 799
 800
 801
 802
 803
 804
 805
 806
 807
 808
 809
 810
 811
 812
 813
 814
 815
 816
 817
 818
 819
 820
 821
 822
 823
 824
 825
 826
 827
 828
 829
 830
 831
 832
 833
 834
 835
 836
 837
 838
 839
 840
 841
 842
 843
 844
 845
 846
 847
 848
 849
 850
 851
 852
 853
 854
 855
 856
 857
 858
 859
 860
 861
 862
 863
 864
 865
 866
 867
 868
 869
 870
 871
 872
 873
 874
 875
 876
 877
 878
 879
 880
 881
 882
 883
 884
 885
 886
 887
 888
 889
 890
 891
 892
 893
 894
 895
 896
 897
 898
 899
 900
 901
 902
 903
 904
 905
 906
 907
 908
 909
 910
 911
 912
 913
 914
 915
 916
 917
 918
 919
 920
 921
 922
 923
 924
 925
 926
 927
 928
 929
 930
 931
 932
 933
 934
 935
 936
 937
 938
 939
 940
 941
 942
 943
 944
 945
 946
 947
 948
 949
 950
 951
 952
 953
 954
 955
 956
 957
 958
 959
 960
 961
 962
 963
 964
 965
 966
 967
 968
 969
 970
 971
 972
 973
 974
 975
 976
 977
 978
 979
 980
 981
 982
 983
 984
 985
 986
 987
 988
 989
 990
 991
 992
 993
 994
 995
 996
 997
 998
 999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
def cal_mag_twostep_hsi(
    magnetic_field: Union[np.ndarray, list],
    reference_magnetic_field: Union[np.ndarray, list],
    max_iterations: int = 2000,
    measurement_noise_std: float = 1e-3,
) -> Tuple[np.ndarray, np.ndarray]:
    """
    The TWOSTEP method proposes a fast, robust algorithm for estimating magnetometer
    biases when the attitude is unknown. This algorithm combines the convergence
    in a single step of a heuristic algorithm currently in use with the correct
    treatment of the statistics of the measurements and does without discarding
    data.

    This algorithm was extended in a second iteration to compute also the soft-iron
    (Alonso, R. Shuster, M.D. (2002b). Complete linear attitude-independent
    magnetometer calibration. Journal of the Astronautical Science, 50(4):477-490).

    Args:
        magnetic_field (numpy.ndarray or list): Magnetic field measurements in a
            3xN or Nx3 numpy array or list.
        reference_magnetic_field (numpy.ndarray or list): Reference magnetic field
            measurements in a 3, or 1x3, or 3x1 numpy array or list.
        max_iterations (int): Maximum number of iterations for the second step.
        measurement_noise_std (float): Standard deviation that characterizes the
            measurements' noise, by default 0.001 G.

    Returns:
        hard_iron (numpy.ndarray): Estimated hard-iron bias as a (3,) numpy array.
        soft_iron (numpy.ndarray): Estimated soft-iron matrix as a (3,3) numpy array.
        calibrated_magnetic_field (numpy.ndarray): Calibrated magnetic field as a
            3xN numpy array.

    Raises:
        TypeError: If the magnetic field or reference magnetic field inputs are not
            numpy arrays or lists.
        ValueError: If the magnetic field input is not a 3xN or Nx3 numpy array, if
            the reference magnetic field input is not a 3, or 1x3, or 3x1 numpy array,
            if the maximum number of iterations is not a positive integer, or if the
            measurement noise standard deviation is not a positive float.
    """
    # Check if the magnetic field input is a list and convert it to a numpy array
    if isinstance(magnetic_field, list):
        magnetic_field = np.array(magnetic_field)

    # Check if the reference magnetic field input is a list and convert it to a numpy array
    if isinstance(reference_magnetic_field, list):
        reference_magnetic_field = np.array(reference_magnetic_field).flatten()

    # Check if the magnetic field input is a numpy array
    if not isinstance(magnetic_field, np.ndarray):
        raise TypeError("The magnetic field input must be a numpy array or a list.")

    # Check if the reference magnetic field input is a numpy array
    if not isinstance(reference_magnetic_field, np.ndarray):
        raise TypeError(
            "The reference magnetic field input must be a numpy array or a list."
        )

    # Check if the magnetic field input is a 3xN or Nx3 numpy array
    if magnetic_field.ndim != 2 or (
        magnetic_field.shape[0] != 3 and magnetic_field.shape[1] != 3
    ):
        raise ValueError("The magnetic field input must be a 3xN or Nx3 numpy array.")

    # Check if the reference magnetic field input is a 3, numpy array
    if reference_magnetic_field.ndim != 1 and reference_magnetic_field.size != 3:
        raise ValueError(
            "The reference magnetic field input must be a 3, or 1x3, or 3x1 numpy array."
        )

    # Force the magnetic field array to be a Nx3 numpy array
    if magnetic_field.shape[0] == 3:
        magnetic_field = magnetic_field.T

    # Check that the maximum number of iterations is a positive integer
    if not isinstance(max_iterations, int) or max_iterations <= 0:
        raise ValueError("The maximum number of iterations must be a positive integer.")

    # Check that the measurement noise standard deviation is a positive float
    if not isinstance(measurement_noise_std, float) or measurement_noise_std <= 0:
        raise ValueError(
            "The measurement noise standard deviation must be a positive float."
        )

    # Compute magnetic field calibration
    mf = magnetic_field

    stop_tol = 1e-24  # Stop Condition from Alonso paper
    I3 = np.eye(3, dtype=np.float64)

    # TWOSTEP Centered estimate
    # Set initial guess for b and D.
    b0 = np.zeros((3, 1))
    d0 = np.zeros((3, 3))

    # Form L matrix, equations (5.10b) and (5.12a)
    l1 = 2 * mf
    l2 = -np.square(mf)
    l3 = -2 * mf[:, [0]] * mf[:, [1]]
    l4 = -2 * mf[:, [0]] * mf[:, [2]]
    l5 = -2 * mf[:, [1]] * mf[:, [2]]
    L_k = np.concatenate([l1, l2, l3, l4, l5], axis=1)

    # Compute sensor error as scalar measurement, equation (5.7a)
    h_matrix = np.ones((mf.shape)) * reference_magnetic_field
    z_k = (
        np.square(np.linalg.norm(mf, axis=1))
        - np.square(np.linalg.norm(h_matrix, axis=1))
    ).reshape(-1, 1)

    # Sensor measurements noise modeled as white gaussian with standard deviation epsilon_k
    epsilon_sq_k = np.ones(mf.shape) * (measurement_noise_std**2)

    # Sensor error scalar measurement noise characterization as gaussian.
    # Gaussian distribution mean, equation (5.14)
    mu_k = -np.sum(epsilon_sq_k, axis=1, keepdims=True)

    # Gaussian distribution variance, equation (5.15)
    sigma_sq_k = (
        4
        * np.einsum(
            "ijk->ikj",
            np.tile(I3 + d0, (mf.shape[0], 1, 1)) @ mf.reshape(-1, 3, 1)
            - np.tile(b0, (mf.shape[0], 1, 1)),
        )
        @ np.apply_along_axis(np.diag, 1, epsilon_sq_k)
        @ (
            np.tile(I3 + d0, (mf.shape[0], 1, 1)) @ mf.reshape(-1, 3, 1)
            - np.tile(b0, (mf.shape[0], 1, 1))
        )
        + 2
        * np.apply_along_axis(
            lambda x: np.square(np.trace(np.diag(x))), 1, epsilon_sq_k
        ).reshape(-1, 1, 1)
    ).reshape(-1, 1)

    # Calculate centered sigma squared, equation (5.18)
    sigma_sq_bar = 1 / np.sum(1 / sigma_sq_k)

    # Center the data, equation (5.19)
    mu_bar, mu_k_tilde = _cal_mag_twostep_center_data(mu_k, sigma_sq_k, sigma_sq_bar)
    z_bar, z_k_tilde = _cal_mag_twostep_center_data(z_k, sigma_sq_k, sigma_sq_bar)
    L_bar, L_k_tilde = _cal_mag_twostep_center_data(L_k, sigma_sq_k, sigma_sq_bar)

    # Compute fisher information matrix
    I_fisher_tilde, I_fishinv_tilde = _cal_mag_twostep_TS_fisher_centered(
        sigma_sq_k, L_k_tilde
    )

    # Compute centered estimate, equation (5.24)
    f_matrix = np.einsum(
        "ijk->jk",
        (
            (1 / sigma_sq_k).reshape(-1, 1, 1)
            * ((z_k_tilde - mu_k_tilde).reshape(-1, 1, 1) * L_k_tilde.reshape(-1, 9, 1))
        ),
    )
    theta_0_tilde = I_fishinv_tilde @ f_matrix

    # TWOSTEP Center correction
    theta_n, theta_np1 = (
        theta_0_tilde,
        theta_0_tilde,
    )  # Initiate theta for  first  iteration
    n = 0  # Initialise  iteration counter
    TS_err = np.inf  # Initial  condition  for  error.

    # ABC is used to remove intensive calculations out of for loop
    abc = -np.einsum(
        "ijk->jk",
        (
            (1 / sigma_sq_k).reshape(-1, 1, 1)
            * ((z_k_tilde - mu_k_tilde).reshape(-1, 1, 1) * L_k_tilde.reshape(-1, 9, 1))
        ),
    )

    while TS_err > stop_tol and n < max_iterations:
        if n != 0:  # If  we are not  in the first	iteration
            theta_n = theta_np1

        # Extract  c  and  E  components
        c, e_matrix = _cal_mag_twostep_theta_to_c_E(theta_n)

        # Compute  second  derivative  of  b^2  wrt theta
        tmp = (
            np.linalg.solve((np.eye(3) + e_matrix), c)
            @ np.linalg.solve((np.eye(3) + e_matrix), c).T
        )
        dbsqdtheta_p = np.concatenate(
            [
                2 * np.linalg.solve((np.eye(3) + e_matrix), c),
                -np.diag(tmp).reshape(3, 1),
                np.vstack([-2 * tmp[0, 1], -2 * tmp[0, 2], -2 * tmp[1, 2]]),
            ]
        )
        # Compute gradient of J
        dJdThetap_tilde = abc + I_fisher_tilde @ theta_n
        dJdThetap_bar = (
            -(1 / sigma_sq_bar)
            * (L_bar.reshape(-1, 1) - dbsqdtheta_p)
            * (
                z_bar
                - (L_bar.reshape(1, -1) @ theta_n)
                + (c.T @ np.linalg.solve((np.eye(3) + e_matrix), c))
                - mu_bar
            )
        )
        dJdTheta = dJdThetap_tilde + dJdThetap_bar

        # Calculate Fisher matrix
        I_fisher_bar = _cal_mag_twostep_TS_fisher_center(
            sigma_sq_bar, L_bar, dbsqdtheta_p
        )

        # Update theta
        theta_np1 = theta_n - np.linalg.solve((I_fisher_tilde + I_fisher_bar), dJdTheta)

        # Compute error
        TS_err = ((theta_np1 - theta_n).T @ (I_fisher_tilde + I_fisher_bar)) @ (
            theta_np1 - theta_n
        )
        n += 1

    b, d_matrix = _cal_mag_twostep_theta_to_b_D(theta_np1)

    # Extract covariance matrix
    m_cd = np.array(
        [
            [b[0, 0], 0, 0, b[1, 0], b[2, 0], 0],
            [0, b[1, 0], 0, b[0, 0], 0, b[2, 0]],
            [0, 0, b[2, 0], 0, b[0, 0], b[1, 0]],
        ]
    )
    m_ed = np.array(
        [
            [2 * d_matrix[0, 0], 0, 0, 2 * d_matrix[0, 1], 2 * d_matrix[0, 2], 0],
            [0, 2 * d_matrix[1, 1], 0, 2 * d_matrix[0, 1], 0, 2 * d_matrix[1, 2]],
            [0, 0, 2 * d_matrix[2, 2], 0, 2 * d_matrix[0, 2], 2 * d_matrix[1, 2]],
            [
                d_matrix[0, 1],
                d_matrix[0, 1],
                0,
                d_matrix[0, 0] + d_matrix[1, 1],
                d_matrix[1, 2],
                d_matrix[0, 2],
            ],
            [
                d_matrix[0, 2],
                0,
                d_matrix[0, 2],
                d_matrix[1, 2],
                d_matrix[0, 0] + d_matrix[2, 2],
                d_matrix[0, 1],
            ],
            [
                0,
                d_matrix[1, 2],
                d_matrix[1, 2],
                d_matrix[0, 2],
                d_matrix[0, 1],
                d_matrix[1, 1] + d_matrix[2, 2],
            ],
        ]
    )
    dbD_dcE = np.eye(9)
    dbD_dcE[:3, :3], dbD_dcE[:3, 3:] = np.eye(3) + d_matrix, m_cd
    dbD_dcE[3:, :3], dbD_dcE[3:, 3:] = np.zeros((6, 3)), 2 * np.eye(6) @ m_ed
    dbD_dcE = np.linalg.inv(dbD_dcE)
    # Cov_est = dbD_dcE @ np.linalg.solve((I_fisher_tilde + I_fisher_bar), dbD_dcE.T)

    # END   TWOSTEP
    hard_iron = (np.linalg.inv(np.eye(3) + d_matrix)) @ b
    soft_iron = np.linalg.inv(np.eye(3) + d_matrix)

    # Calibrate magnetic field
    calibrated_magnetic_field = magnetic_field.copy()[..., np.newaxis]
    N = magnetic_field.shape[0]
    calibrated_magnetic_field = calibrated_magnetic_field - np.tile(
        hard_iron.reshape(3, 1), (N, 1, 1)
    )
    calibrated_magnetic_field = (
        np.tile(np.linalg.inv(soft_iron), (N, 1, 1)) @ calibrated_magnetic_field
    ).squeeze()

    return hard_iron.flatten(), soft_iron, calibrated_magnetic_field