Class MagneticModel

Class Documentation

class MagneticModel

Earth magnetic model.

The GAZEBO model is a special instance of IGRF-14 on 22/01/2018, which corresponds to the baked-in data table used by the Gazebo Magnetometer system.

Public Types

using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeClockInterface, NodeLoggingInterface>

Public Functions

MagneticModel(RequiredInterfaces node, const std::string &name, const std::string &modelPath, bool strict)

Create the magnetic model.

Parameters:
  • node[in] The node to use.

  • name[in] Name of the model (e.g. “wmm2020”).

  • modelPath[in] Path to the folder with stored models. If empty, a default system location will be used.

  • strict[in] Whether to fail if the magnetic model is used outside its natural validity bounds.

virtual ~MagneticModel()
virtual bool isValid(const rclcpp::Time &time) const

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

Parameters:

time[in] The time of validity.

Returns:

Whether the model is valid (regardless of strictness).

virtual bool isValid(int year) const

Tell whether this model is valid at the given year.

Parameters:

year[in] The year of validity.

Returns:

Whether the model is valid (regardless of strictness).

virtual cras::expected<MagneticField, std::string> getMagneticField(const sensor_msgs::msg::NavSatFix &fixMsg, const rclcpp::Time &stampIn) const

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

Parameters:
  • fixMsg[in] The place for which magnetic field is queried. Timestamp from the message is ignored.

  • stampIn[in] The time for which magnetic field is queried.

Returns:

The magnetic field.

virtual cras::expected<MagneticFieldComponentProperties, std::string> getMagneticFieldComponents(const sensor_msgs::msg::NavSatFix &fixMsg, const rclcpp::Time &stampIn) const

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

Parameters:
  • fixMsg[in] The place for which magnetic field components are queried. Timestamp from the message is ignored.

  • stampIn[in] The time for which magnetic field components are queried.

Returns:

The magnetic field components.

virtual cras::expected<MagneticFieldComponentProperties, std::string> getMagneticFieldComponents(const MagneticField &field, const rclcpp::Time &stampIn) const

Get the components of the measured magnetic field.

Parameters:
  • field[in] The measured magnetic field.

  • stampIn[in] The time for which magnetic field components are queried.

Returns:

The magnetic field components.

Public Static Attributes

static const char *GAZEBO

Gazebo model name.

static const char *IGRF14

IGRF-14 model name.

static const char *WMM2010

WMM 2010 model name.

static const char *WMM2015

WMM 2015v2 model name.

static const char *WMM2020

WMM 2020 model name.

static const char *WMM2025

WMM 2025 model name.

Protected Attributes

bool strict = {true}

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

std::unique_ptr<MagneticModelPrivate> data

PIMPL data.

RequiredInterfaces node