Time to give your magnetometers a big refresh!

Are you using magnetometers on your robot? And are you using them right? Did you know each magnetometer has a bias that needs to be removed?


I’d like to announce the release of our suite of magnetometer tools that could be helpful to lots of people who deal with outdoor navigation.

The release is for ROS Noetic currently. We’ll definitely port the stack to ROS 2 some time next year.

I’ll be happy for feedback!

magnetometer_pipeline

To calibrate your magnetometer (i.e. identify its bias), use node magnetometer_pipeline/ magnetometer_bias_observer . Just spin up the node, call service /calibrate_magnetometer and you have 30 seconds to rotate your robot about as many axes as you can. This corresponds to the 8-shape phones sometimes want you to do.

Using a magnetometer without calibration is bad, bad, bad! The outputs are usually pretty much nonsense. Do not do it.

Once the magnetometer is calibrated, bias is published on topic /imu/mag_bias. Node (and nodelet) magnetometer_pipeline/magnetometer_bias_remover can take the raw /imu/mag data and remove the bias from them, providing topic /imu/mag_unbiased.

magnetometer_compass

To convert the magnetometer measurement to a heading, use node(let) magnetometer_compass/magnetometer_compass. It eats /imu/mag_unbiased and /imu/data (with orientation) and extracts azimuth (heading).

As there are multiple possible ways to express azimuths, magnetometer_compass supports all imaginable combinations:

Azimuth reference:

  • Magnetic North (compliant with physical compasses)
  • Geographic (true) North (compliant with maps)
  • UTM North (compliant with the UTM projection - a Cartesian projection of Earth, used e.g. by robot_localization)

Azimuth orientation:

  • ENU (East-North-Up, compliant with REP-103)
  • NED (North-East-Down, compliant with physical compasses)

Units:

  • degrees (compliant with humans)
  • radians (compliant with REP-103)

Output data types:

To be able to convert between magnetic and true North, magnetic declination needs to be known. This value depends on GNSS position, so the compass node can eat NavSatFix messages which tell it where the robot is. Or, if the position is predictable/static, you can set it as a config parameter and then you don’t need to provide the NavSatFix messages. The resolution of the magnetic model is ~3500 km, so you don’t need to be very precise here.

Magnetometer measurements can be quite noisy. Therefore, magnetometer_compass contains a built-in low-pass filter with configurable strength to make the azimuth reading a bit more stable.

Once you get the magnetometer_compass running, you might want to visualize its output using magnetometer_compass/visualize_azimuth, which can eat any of the above-defined outputs.

Some magnetometer drivers (ethzasl_xsens_driver, I’m looking at you) mix up the units in the magnetometer part and report in Gauss instead of Tesla (1 T = 10000 G). Fortunately, for just identifying the azimuth, this is no problem!

compass_conversions

As can be seen above, there are quite a lot of ways to express an azimuth. compass_conversions provide a C++ library, message filter and nodelet that can convert any kind of azimuth to any other kind.

Using the message filter, it is quite simple to subscribe to any kind of azimuth representation and get the one you actually need in your code:

message_filters::Subscriber azimuthInput(...);
message_filters::Subscriber fixInput(...);
compass_conversions::CompassFilter filter(log, nullptr, azimuthInput, fixInput,
  compass_msgs::Azimuth::UNIT_RAD, compass_msgs::Azimuth::ORIENTATION_ENU,
  compass_msgs::Azimuth::REFERENCE_GEOGRAPHIC);
filter.registerCallback([](const compass_msgs::AzimuthConstPtr& msg) {
  ...  // Handle the data which come geographic-referenced, ENU oriented, in radians
});

Analogically, you can spin up compass_conversions/compass_transformer to do this conversion at the ROS API level.

magnetic_model

Converting magnetic North to true North requires knowing the magnetic declination. This is a value provided by World Magnetic Model. magnetic_model is a C++ library that provides easy usage of the model with ROS data types. In addition to what GeographicLib already provides, magnetic_model also knows the error model of the conversion, so it can also tell you the variance of the conversion.

This package comes with all available releases of WMM preinstalled, so there’s no need to get the data elsewhere. But it still supports customizing the path to the folder with models - just in case you need to use something different.

9 Likes