|
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Go to the documentation of this file.
7 #ifndef PARAM_PROVIDER_H
8 #define PARAM_PROVIDER_H
12 #include <yaml-cpp/yaml.h>
13 #include <ros/node_handle.h>
41 ParamProvider(
const ros::NodeHandle& nh, std::string node_name,
const bool use_rosparam =
true);
64 bool getParam(
const std::string& param_name, T& value_out)
const;
77 bool getParam(
const std::string& param_name, XmlRpc::XmlRpcValue& value_out)
const;
81 std::vector<YAML::Node> m_yamls;
83 std::string m_node_name;
87 bool getParamImpl(
const std::string& param_name, T& value_out)
const;
89 std::optional<YAML::Node> findYamlNode(
const std::string& param_name)
const;
94 #include "mrs_lib/impl/param_provider.hpp"
96 #endif // PARAM_PROVIDER_H
bool addYamlFile(const std::string &filepath)
Add a YAML file to be parsed and used for loading parameters.
Definition: param_provider.cpp:18
ParamProvider(const ros::NodeHandle &nh, std::string node_name, const bool use_rosparam=true)
Main constructor.
Definition: param_provider.cpp:13
bool getParam(const std::string ¶m_name, T &value_out) const
Gets the value of a parameter.
Definition: param_provider.hpp:9
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
Helper class for ParamLoader.
Definition: param_provider.h:30