Magnetometer calibration issue on large robot

I posted a question similar to this on the ros-wrapper github (https://github.com/stereolabs/zed-ros-wrapper/issues/889#issuecomment-1532585864) but have further questions, not related to ROS.

The problem: we use ZED2i cameras mounted on large (400kg) robots. Because of size/weight we can’t rotate the robots over 360deg in all directions to calibrate the magnetometer. When we try a calibration, obviously the ellipsoid fitting on the roll and tilt axis is bad, the optimised ellipsoid just covering the data points we have, resulting in very flat ellipsoids. This then fails to save, maybe because of a numerical instability (it just says the save failed).

I have played with other procedures to calibrate magnetometers that at least did not fail in such a situation. For example the one in rtimulib2.

So my questions.

If the magnetometer is not calibrated, are the “working” parts of the IMU used when doing performing pose tracking? Or is the magnetic data fused in anyway, resulting in a bad output? Or is it purely based on visual odometry?

If I come up with another calibration procedure, is the calibration file format available so that I can generate the file and make the ZED API use the IMU correctly?

How are people using these on large vehicles (or devices) do the calibration is they can’t rotate the device over the full rotations?

Cheers,

The Positional Tracking module of the ZED SDK does not fuse magnetometer information, only Visual Odometry and Inertial information.

No, this is not possible because the calibration of the IMU is performed in the factory with precise robotics arms and we do not provide methods to overwrite it.
The ZED SDK allows you to retrieve the RAW IMU data in order to perform your own calibration.

They perform a 2D calibration on the X/Y plane by using external tools.

Thanks for that. Glad that the pose tracking would still work.

I don’t understand why I can’t save the calibration myself. When I perform a magnetometer calibration, a file gets saved as a result of this. Why can I not write this file using another application? Not being able to save the calibration also implies that I need to then fuse the raw gyro and accelerometer data myself to essentially create my own IMU.

A 2D calibration is not good enough for us as we work on off-road (difficult terrain) robots that can roll and tilt to about 45deg.

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):