Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
37 changes: 36 additions & 1 deletion proto/gz/msgs/magnetometer.proto
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
/*
* Copyright (C) 2017 Open Source Robotics Foundation
* Copyright (C) 2026 Rudis Laboratories
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -30,9 +31,43 @@ import "gz/msgs/vector3d.proto";
/// \brief Message that encapsulates sensor data from a magnetometer.
message Magnetometer
{
/// \brief Units for the magnetic field measurement.
enum MagneticFieldUnit
{
/// \brief Gauss (1 G = 1e-4 T). Default.
GAUSS = 0;

/// \brief Tesla (SI unit).
TESLA = 1;
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

For all of our other sensors, I believe we require that measurements to be in SI units and ENU coordinates, correct? What is the benefit of diverging from that pattern here?

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well, want to guess what units and coordinate frame our current magnetometer is publishing in?

Copy link
Copy Markdown
Member Author

@bperseghetti bperseghetti Mar 8, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here's the SDF specification:
https://sdformat.org/spec/1.12/world/#world_magnetic_field

Now here's the test world values (roughly gauss units, but maybe it's some arbitrary environment):
https://github.com/gazebosim/gz-sim/blame/5049587241f63826dca7fd9a4b501d1ba91a0a73/test/worlds/magnetometer.sdf#L4

Here's what happens when you take that same world, don't define a magnetic field and instead just allow it to use spherical coordinates (in this case Tokyo):

<sdf version="1.6">
  <world name="magnetometer_sensor">
    <physics name="1ms" type="ode">
      <max_step_size>0.001</max_step_size>
      <real_time_factor>0</real_time_factor>
    </physics>
    <plugin
      filename="gz-sim-physics-system"
      name="gz::sim::systems::Physics">
    </plugin>
    <plugin
      filename="gz-sim-magnetometer-system"
      name="gz::sim::systems::Magnetometer">
    </plugin>
    <plugin
      filename="gz-sim-scene-broadcaster-system"
      name="gz::sim::systems::SceneBroadcaster">
    </plugin>
    <spherical_coordinates>
      <surface_model>EARTH_WGS84</surface_model>
      <latitude_deg>35.6762</latitude_deg>
      <longitude_deg>139.6503</longitude_deg>
      <elevation>0</elevation>
      <heading_deg>0</heading_deg>
    </spherical_coordinates>
    
    <model name="ground_plane">
..........

This outputs:
image

Copy link
Copy Markdown
Member Author

@bperseghetti bperseghetti Mar 8, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Except the test world has the magnetometer with some rotations applied to it, so then remove those:

    <model name="magnetometer_model">
      <pose>4 0 3.0 0 0.0 0</pose>
      <link name="link">
        <pose>0.05 0.05 0.05 0 0 0</pose>
        <inertial>
          <mass>0.1</mass>

Granted this uses the old crude approximation method that as of today an "expired epoch".
image

field_tesla {
  x: 0.29964852333068837
  y: -0.04052930325269713
  z: 0.353400468826294
}

Copy link
Copy Markdown
Member Author

@bperseghetti bperseghetti Mar 8, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The Official WMM for that exact same location in NED and nT gives:
x: 30086.0
y: -4179.3
z: 35641.7

or if you want it in Tesla (still the NED truth data):
x: 0.0000300860
y: -0.0000041793
z: 0.0000356417

Now for Gauss (still the NED truth data):
x: 0.300860
y: -0.041793
z: 0.356417

As you can see though, our unchanged current magnetometer is actually outputting NED Gauss...

And while I'm willing to allow for declaration of "Gauss" as the default since that's a meaningful unit for a magnetometer (compared to Tesla) the NED should not be the default and is definitely a MASSIVE BUG IMO:
https://xkcd.com/1172

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the easy obvious one here is that since this is protobuf, if you don't change from the default, the fields don't even show up. It breaks nobody. If for some reason you really need your output in NED or some other units, then by all means change it, but then that should show in the message.

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, what you write holds for people looking at gz topic. But that's a minority case I'd say. Tha majority case is code looking at the field. And code has to look at the field in any case. And then all subscribers need to implement the conversion routines because what if somebody decided to use nT. It seems that this is a quite high price for this little convenience.

Copy link
Copy Markdown
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not sure I follow, protobuf messages are for gazebo, not for ROS, those get converted anyhow for ROS, that conversion is trivial if we can say what frame and unit it is in. Have you ever used Ardupilot, PX4 or any POSIX rtos connected to gazebo before?

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, now I don't know if I follow... What do these systems have in common with the topic in this PR? Do they only support float32 or something like that? And if you're using SITL/HITL, you anyways need a bridge between Gazebo and the system, which usually runs on the full-fledged system... So your PX4 can happily send Gauss and the bridge can translate to Tesla.

Copy link
Copy Markdown
Member Author

@bperseghetti bperseghetti Mar 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the main thing is they take direct gz-transport messages and use gauss native internally. Anyone can convert anything anywhere... If they know what it is... I'm fine with throwing everyone under the bus and forcing it to ENU and Tesla if we are that scared/worried of enums in a single protobuf message...

I mean, people do realize that Gauss is the actual true unit of measure and that Tesla was a made up unit in 1960 to honor an "inventor" who didn't even believe in the electron let alone do ANYTHING for E&M theory or math that describes the magnetic field...

"In 1833, Carl_Friedrich_Gauss, head of the Geomagnetic Observatory in Göttingen, published a paper on measurement of the Earth's magnetic field.[12] It described a new instrument that consisted of a permanent bar magnet suspended horizontally from a gold fibre. The difference in the oscillations when the bar was magnetised and when it was demagnetised allowed Gauss to calculate an absolute value for the strength of the Earth's magnetic field.[13] The gauss, the CGS unit of magnetic flux density was named in his honour"

This is like a new measurement system coming out in 2060 for electromotive force and it gets the name "Musk" and happens to have units of 10^5 Volts.... Just so we can make sure we count all the zeros proceeding our lithium cells charge...


/// \brief Microtesla (1 uT = 1e-6 T).
MICRO_TESLA = 2;

/// \brief Nanotesla (1 nT = 1e-9 T).
NANO_TESLA = 3;
}

/// \brief Coordinate frame convention for the field vector.
enum CoordinateFrame
{
/// \brief East-North-Up. Default.
ENU = 0;

/// \brief North-East-Down.
NED = 1;
}

/// \brief Optional header data
Header header = 1;

/// \brief Magnetic field strength (in Tesla) along body-frame axis
/// \brief Magnetic field vector along body-frame axes.
/// The unit and coordinate frame are indicated by the unit and frame fields.
/// Field name kept as field_tesla for protobuf backward compatibility.
Vector3d field_tesla = 2;

/// \brief Unit of the magnetic field measurement.
MagneticFieldUnit unit = 3;

/// \brief Coordinate frame convention of the field vector.
CoordinateFrame frame = 4;
}
Loading