|
void MagnetometerPrivate::Update( |
|
const EntityComponentManager &_ecm) |
|
{ |
|
GZ_PROFILE("MagnetometerPrivate::Update"); |
|
_ecm.Each<components::Magnetometer, |
|
components::WorldPose>( |
|
[&](const Entity &_entity, |
|
const components::Magnetometer * /*_magnetometer*/, |
|
const components::WorldPose *_worldPose)->bool |
|
{ |
|
auto it = this->entitySensorMap.find(_entity); |
|
if (it != this->entitySensorMap.end()) |
|
{ |
|
// Get the magnetometer physical position |
|
const math::Pose3d &magnetometerWorldPose = _worldPose->Data(); |
|
it->second->SetWorldPose(magnetometerWorldPose); |
|
|
|
// Position |
|
auto latLonEle = sphericalCoordinates(_entity, _ecm); |
|
if (!latLonEle) |
|
{ |
|
gzwarn << "Failed to update Magnetometer sensor entity [" << _entity |
|
<< "]. Spherical coordinates not set." << std::endl; |
|
return true; |
|
} |
|
|
|
auto lat_rad = GZ_DTOR(latLonEle.value().X()); |
|
auto lon_rad = GZ_DTOR(latLonEle.value().Y()); |
|
|
|
// Magnetic declination and inclination (radians) |
|
float declination_rad = |
|
get_mag_declination( |
|
lat_rad * 180 / GZ_PI, lon_rad * 180 / GZ_PI) * GZ_PI / 180; |
|
float inclination_rad = |
|
get_mag_inclination( |
|
lat_rad * 180 / GZ_PI, lon_rad * 180 / GZ_PI) * GZ_PI / 180; |
|
|
|
// Magnetic strength in gauss (10^5 nano tesla = 10^-2 centi gauss) |
|
float strength_ga = |
|
0.01f * |
|
get_mag_strength(lat_rad * 180 / GZ_PI, lon_rad * 180 / GZ_PI); |
|
|
|
// Magnetic intensity measured in telsa |
|
float strength_tesla = 1.0E-4 * strength_ga; |
|
|
|
// Magnetic field components are calculated in world NED frame using: |
|
// http://geomag.nrcan.gc.ca/mag_fld/comp-en.php |
|
float H = cosf(inclination_rad); |
|
H *= this->useUnitsGauss ? strength_ga : strength_tesla; |
|
float Z_ned = tanf(inclination_rad) * H; |
|
float X_ned = H * cosf(declination_rad); |
|
float Y_ned = H * sinf(declination_rad); |
|
|
|
float X = X_ned; |
|
float Y = Y_ned; |
|
float Z = Z_ned; |
|
if (!this->useEarthFrameNED) |
|
{ |
|
// Use ENU convention for earth frame. |
|
X = Y_ned; |
|
Y = X_ned; |
|
Z = -1.0 * Z_ned; |
|
} |
|
|
|
math::Vector3d magnetic_field_I(X, Y, Z); |
|
it->second->SetWorldMagneticField(magnetic_field_I); |
|
} |
|
else |
|
{ |
|
gzerr << "Failed to update magnetometer: " << _entity << ". " |
|
<< "Entity not found." << std::endl; |
|
} |
|
|
|
return true; |
|
}); |
|
} |
gz-sim/src/systems/magnetometer/Magnetometer.cc
Lines 441 to 516 in 9a6478a
As you can see the magnetometer only writes to world magnetic field but never uses the world magnetic field which is set by the sdf during the formation of this entity
It just uses a lookup table that has prefilled values to calculate the magnetic field according to the magnetometer's pose in the world
If this is an intended behavior than world magnetic field parameter would be misleading to show to the user and if we want to keep showing world magnetic field we need to give it some meaning as few people might want to change the default values to see the effect of that on the magnetometer. For that I propose that we add another param to the magnetometer that can be set through sdf and that would allow magnetometer to either use the pre computed lookup table or calculate magnetic field based on its pose and world magnetic field