Go to the documentation of this file.
17 #include <geometry_msgs/Vector3.h>
19 #include <sensor_msgs/MagneticField.h>
20 #include <sensor_msgs/NavSatFix.h>
30 sensor_msgs::MagneticField
field;
31 geometry_msgs::Vector3
dt;
56 struct MagneticModelPrivate;
92 virtual bool isValid(
int year)
const;
101 const sensor_msgs::NavSatFix& fix,
const ros::Time& stamp)
const;
110 const sensor_msgs::NavSatFix& fix,
const ros::Time& stamp)
const;
126 std::unique_ptr<MagneticModelPrivate>
data;
double declination
Declination of the vector (angle from North towards East) [rad].
Components into which a 3D magnetic vector can be decomposed.
static const char * WMM2015
WMM 2015v2 model name.
virtual cras::expected< MagneticField, std::string > getMagneticField(const sensor_msgs::NavSatFix &fix, const ros::Time &stamp) const
Get the magnetic field vector on the provided place on Earth.
double inclination
Inclination of the vector (angle from horizontal direction downwards) [rad].
double totalMagnitude
Total magnitude of the vector [T].
std::unique_ptr< MagneticModelPrivate > data
PIMPL data.
static const char * WMM2020
WMM 2020 model name.
bool strict
If true, the magnetic model will fail if it is used outside its bounds.
static const char * WMM2010
WMM 2010 model name.
virtual cras::expected< MagneticFieldComponentProperties, std::string > getMagneticFieldComponents(const sensor_msgs::NavSatFix &fix, const ros::Time &stamp) const
Get the magnetic field components on the provided place on Earth.
geometry_msgs::Vector3 dt
Time derivative of the field [T/year].
geometry_msgs::Vector3 error
Standard deviations of the magnetic field vector components.
MagneticFieldComponents errors
Standard deviations of the components [T or rad].
::cras::LogHelper::Ptr LogHelperPtr
MagneticModel(const cras::LogHelperPtr &log, const std::string &name, const std::string &modelPath, bool strict)
Create the magnetic model.
virtual bool isValid(const ros::Time &time) const
Tell whether this model is valid at the given time instant.
Properties of a local magnetic field vector.
static const char * WMM2025
WMM 2025 model name.
Magnetic field components together with their time derivatives and error terms.
sensor_msgs::MagneticField field
The computed magnetic field vector in ENU convention [T].
double horizontalMagnitude
Magnitude of the horizontal component [T].
MagneticFieldComponents dt
Time derivatives of the components [T/year or rad/year].
MagneticFieldComponents values
Values of the components [T or rad].
magnetic_model
Author(s): Martin Pecka
autogenerated on Wed Jan 8 2025 04:03:10