magnetic_model::MagneticModel Class Reference

Earth magnetic model. More...

#include <magnetic_model.h>

Inheritance diagram for magnetic_model::MagneticModel:

Public Member Functions

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. More...
 
virtual cras::expected< MagneticFieldComponentProperties, std::string > getMagneticFieldComponents (const MagneticField &field, const ros::Time &stamp) const
 Get the components of the measured magnetic field. More...
 
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. More...
 
virtual bool isValid (const ros::Time &time) const
 Tell whether this model is valid at the given time instant. More...
 
virtual bool isValid (int year) const
 Tell whether this model is valid at the given year. More...
 
 MagneticModel (const cras::LogHelperPtr &log, const std::string &name, const std::string &modelPath, bool strict)
 Create the magnetic model. More...
 
virtual ~MagneticModel ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Static Public Attributes

static const char * WMM2010
 WMM 2010 model name. More...
 
static const char * WMM2015
 WMM 2015v2 model name. More...
 
static const char * WMM2020
 WMM 2020 model name. More...
 
static const char * WMM2025
 WMM 2025 model name. More...
 

Protected Attributes

std::unique_ptr< MagneticModelPrivate > data
 PIMPL data. More...
 
bool strict {true}
 If true, the magnetic model will fail if it is used outside its bounds. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

Earth magnetic model.

Definition at line 61 of file magnetic_model.h.

Constructor & Destructor Documentation

◆ MagneticModel()

magnetic_model::MagneticModel::MagneticModel ( const cras::LogHelperPtr log,
const std::string &  name,
const std::string &  modelPath,
bool  strict 
)

Create the magnetic model.

Parameters
[in]logThe logger.
[in]nameName of the model (e.g. "wmm2020").
[in]modelPathPath to the folder with stored models. If empty, a default system location will be used.
[in]strictWhether to fail if the magnetic model is used outside its natural validity bounds.

◆ ~MagneticModel()

virtual magnetic_model::MagneticModel::~MagneticModel ( )
virtual

Member Function Documentation

◆ getMagneticField()

virtual cras::expected<MagneticField, std::string> magnetic_model::MagneticModel::getMagneticField ( const sensor_msgs::NavSatFix &  fix,
const ros::Time stamp 
) const
virtual

Get the magnetic field vector on the provided place on Earth.

Parameters
[in]fixThe place for which magnetic field is queried. Timestamp from the message is ignored.
[in]stampThe time for which magnetic field is queried.
Returns
The magnetic field.

◆ getMagneticFieldComponents() [1/2]

virtual cras::expected<MagneticFieldComponentProperties, std::string> magnetic_model::MagneticModel::getMagneticFieldComponents ( const MagneticField field,
const ros::Time stamp 
) const
virtual

Get the components of the measured magnetic field.

Parameters
[in]fieldThe measured magnetic field.
[in]stampThe time for which magnetic field components are queried.
Returns
The magnetic field components.

◆ getMagneticFieldComponents() [2/2]

virtual cras::expected<MagneticFieldComponentProperties, std::string> magnetic_model::MagneticModel::getMagneticFieldComponents ( const sensor_msgs::NavSatFix &  fix,
const ros::Time stamp 
) const
virtual

Get the magnetic field components on the provided place on Earth.

Parameters
[in]fixThe place for which magnetic field components are queried. Timestamp from the message is ignored.
[in]stampThe time for which magnetic field components are queried.
Returns
The magnetic field components.

◆ isValid() [1/2]

virtual bool magnetic_model::MagneticModel::isValid ( const ros::Time time) const
virtual

Tell whether this model is valid at the given time instant.

Parameters
[in]timeThe time of validity.
Returns
Whether the model is valid (regardless of strictness).

◆ isValid() [2/2]

virtual bool magnetic_model::MagneticModel::isValid ( int  year) const
virtual

Tell whether this model is valid at the given year.

Parameters
[in]yearThe year of validity.
Returns
Whether the model is valid (regardless of strictness).

Member Data Documentation

◆ data

std::unique_ptr<MagneticModelPrivate> magnetic_model::MagneticModel::data
protected

PIMPL data.

Definition at line 126 of file magnetic_model.h.

◆ strict

bool magnetic_model::MagneticModel::strict {true}
protected

If true, the magnetic model will fail if it is used outside its bounds.

Definition at line 123 of file magnetic_model.h.

◆ WMM2010

const char* magnetic_model::MagneticModel::WMM2010
static

WMM 2010 model name.

Definition at line 64 of file magnetic_model.h.

◆ WMM2015

const char* magnetic_model::MagneticModel::WMM2015
static

WMM 2015v2 model name.

Definition at line 65 of file magnetic_model.h.

◆ WMM2020

const char* magnetic_model::MagneticModel::WMM2020
static

WMM 2020 model name.

Definition at line 66 of file magnetic_model.h.

◆ WMM2025

const char* magnetic_model::MagneticModel::WMM2025
static

WMM 2025 model name.

Definition at line 67 of file magnetic_model.h.


The documentation for this class was generated from the following file:


magnetic_model
Author(s): Martin Pecka
autogenerated on Wed Jan 8 2025 04:03:10