Magnetometer calibration issue on large robot

Very late reply, but I just submitted a pull request to publish the uncalibrated magnetometer field values (Add support for publishing magnetometer heading and uncalibrated field values by thandal · Pull Request #211 · stereolabs/zed-ros2-wrapper · GitHub). The field values have already been rotated into a level frame, just like the calibrated values.

I found that I was able to get a much better ~2D calibration (in a wheeled vehicle) by doing the following:

  1. collect a log file while driving around in circles and figure-eights on various sloped surfaces
  2. for each of the field axes (x, y, z), do a simple hard-iron calibration by subtracting the per-axis median, and then scaling by the maximum of all the fields.
  3. Then of course you have to correct for the magnetic declination…

A python snippet:

    # Uncalibrated magnetic field values *appear* to be in a level frame already!
    zed_mag_raw_field = np.array((zed_mag_raw.magnetic_field_x.array,
                                  zed_mag_raw.magnetic_field_y.array,
                                  zed_mag_raw.magnetic_field_z.array)).T
    # Rudimentary hard iron calibration -- limited manipulation for pitch and roll...
    mag_offset = np.median(zed_mag_raw_field, axis=0)
    print(f"{mag_offset=}")
    zed_mag_raw_field -= mag_offset
    mag_scale = np.max(zed_mag_raw_field)
    print(f"{mag_scale=}")
    zed_mag_raw_field /= mag_scale

This yields an axis-vs-axis plot that looks like this:
image

The result compares very well with gnss-derived ‘fix yax’ (which is noisy when the vehicle is slow or stopped):