Class MagneticModelManager
Defined in File magnetic_model_manager.hpp
Class Documentation
-
class MagneticModelManager
Earth magnetic model.
Public Types
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface
-
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface
-
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeClockInterface, NodeLoggingInterface>
Public Functions
-
explicit MagneticModelManager(RequiredInterfaces node, const std::optional<std::string> &modelPath = {})
Create magnetic model manager.
- Parameters:
node – [in] The node to use.
modelPath – [in] Path to the folder with stored models. If nullopt, the default data distributed with this package will be used. If empty string, a default system location will be used. The default system location is determined by GeographicLib and can be influenced by setting environment variables
GEOGRAPHICLIB_MAGNETIC_PATHorGEOGRAPHICLIB_DATA.
-
virtual ~MagneticModelManager()
-
std::string getModelPath() const
Get the model path.
- Returns:
Path to the folder with stored models. If empty, a default system location will be used.
-
void setModelPath(const std::optional<std::string> &modelPath)
Set the path to the folder with stored models.
- Parameters:
modelPath – [in] Path to the folder with stored models. If nullopt, the default data distributed with this package will be used. If empty string, a default system location will be used. The default system location is determined by GeographicLib and can be influenced by setting environment variables
GEOGRAPHICLIB_MAGNETIC_PATHorGEOGRAPHICLIB_DATA.
-
virtual std::string getBestMagneticModelName(const rclcpp::Time &date) const
Get the best magnetic model for the given date.
- Parameters:
date – [in] The date in question.
- Returns:
Name of the best magnetic model. If forcedMagneticModelName is non-empty, this value is always returned.
-
virtual cras::expected<std::shared_ptr<MagneticModel>, std::string> getMagneticModel(const rclcpp::Time &stamp, bool strict) const
Get the most suitable magnetic model for the given year.
- Parameters:
stamp – [in] The time for which model should be returned.
strict – [in] Whether the returned model should fail if data outside its validity range are queried.
- Returns:
The magnetic model or error if there is no suitable model.
-
virtual cras::expected<std::shared_ptr<MagneticModel>, std::string> getMagneticModel(const std::string &name, bool strict) const
Get the magnetic model with the given name.
- Parameters:
name – [in] Name of the model. Check MagneticModel constants to see possible values.
strict – [in] Whether the returned model should fail if data outside its validity range are queried.
- Returns:
The magnetic model or error if it cannot be found.
Protected Attributes
-
std::unique_ptr<MagneticModelManagerPrivate> data
PIMPL data.
-
RequiredInterfaces node
-
using NodeClockInterface = rclcpp::node_interfaces::NodeClockInterface