13#include <yaml-cpp/yaml.h>
14#include <rclcpp/rclcpp.hpp>
27 std::ostream&
operator<<(std::ostream& os,
const std::vector<T>& var);
36 template <
typename Key,
typename Value>
37 std::ostream&
operator<<(std::ostream& os,
const std::map<Key, Value>& var);
46 std::ostream&
operator<<(std::ostream& os, rclcpp::ParameterType& var);
58 concept numeric = (std::integral<T> || std::floating_point<T>) && !std::same_as<T, bool>;
100 template <
typename T>
108 std::optional<range_t<T>>
range = std::nullopt;
116 template <
typename T>
126 std::optional<std::string>
prefix = std::nullopt;
136 template <
typename T>
140 std::optional<std::string>
prefix = std::nullopt;
151 ParamProvider(
const std::shared_ptr<rclcpp::Node>& node,
const bool use_rosparam =
true);
180 template <
typename T>
181 bool getParam(
const std::string& param_name, T& value_out)
const;
195 template <
typename T>
196 bool getParam(
const resolved_name_t& resolved_name, T& value_out,
const get_options_t<T>& opts = {})
const;
207 template <
typename T>
208 bool setParam(
const std::string& param_name,
const T& value)
const;
221 template <
typename T>
222 bool setParam(
const resolved_name_t& resolved_name,
const T& value,
const set_options_t<T>& opts = {})
const;
232 template <
typename T>
244 template <
typename T>
245 bool declareParam(
const std::string& param_name,
const T& default_value)
const;
257 template <
typename T>
258 bool declareParam(
const resolved_name_t& resolved_name,
const declare_options_t<T>& opts = {})
const;
268 void setPrefix(
const std::string& prefix);
283 resolved_name_t
resolveName(
const std::string& param_name)
const;
286 std::vector<std::shared_ptr<YAML::Node>> m_yamls;
287 std::shared_ptr<rclcpp::Node> m_node;
288 std::string m_node_name;
290 std::string m_prefix;
292 std::optional<YAML::Node> findYamlNode(
const resolved_name_t& resolved_name)
const;
294 template <
typename T>
295 bool ranges_match(
const rcl_interfaces::msg::ParameterDescriptor& descriptor,
const range_t<T>& declare_range)
const;
297 template <
typename T>
298 bool loadFromYaml(
const resolved_name_t& resolved_name, T& value_out,
const get_options_t<T>& opts)
const;
300 template <
typename T>
301 bool loadFromROS(
const resolved_name_t& resolved_name, T& value_out,
const get_options_t<T>& opts)
const;
307#ifndef PARAM_PROVIDER_HPP
Helper class for ParamLoader and DynparamMgr.
Definition param_provider.h:73
bool addYamlFile(const std::string &filepath)
Add a YAML file to be parsed and used for loading parameters.
Definition param_provider.cpp:52
void setPrefix(const std::string &prefix)
Sets a prefix that will be applied to parameter names before subnode namespaces.
Definition param_provider.cpp:138
resolved_name_t resolveName(const std::string ¶m_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:148
bool getParam(const std::string ¶m_name, T &value_out) const
Gets the value of a parameter.
Definition param_provider.hpp:78
std::string getPrefix() const
Returns the current parameter name prefix.
Definition param_provider.cpp:143
bool declareParam(const std::string ¶m_name) const
Defines a parameter.
Definition param_provider.hpp:171
bool setParam(const std::string ¶m_name, const T &value) const
Sets the value of a parameter to ROS.
Definition param_provider.hpp:129
void copyYamls(const ParamProvider ¶m_provider)
Copy parsed YAMLs from another ParamProvider.
Definition param_provider.cpp:80
Convenience concept of a numeric value (i.e. either integral or floating point, and not bool).
Definition param_provider.h:58
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
std::ostream & operator<<(std::ostream &os, const Eigen::MatrixX< T > &var)
Helper overload for printing of Eigen matrices.
Definition param_loader.hpp:21
rclcpp::ParameterType to_param_type()
Convenince function to get the corresponding rclcpp::ParamType from a C++ type.
Definition param_provider.hpp:70
Implements ParamProvider - a convenience class for seamlessly loading parameters from YAML or ROS.
Struct of options when declaring a parameter to ROS.
Definition param_provider.h:102
bool reconfigurable
If true, the parameter will be dynamically reconfigurable, otherwise it will be declared as read-only...
Definition param_provider.h:104
std::optional< T > default_value
An optional default value to initialize the parameter with.
Definition param_provider.h:106
std::optional< range_t< T > > range
An optional range of valid values of the parameter (only for numerical types).
Definition param_provider.h:108
Struct of options when getting a parameter from ROS.
Definition param_provider.h:118
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:128
std::optional< bool > use_rosparam
Specifies whether the parameter should be attempted to be loaded from ROS if it cannot be loaded from...
Definition param_provider.h:124
bool always_declare
Iff true, the parameter will be declared to ROS even if it's value was loaded from a YAML.
Definition param_provider.h:120
bool use_yaml
Iff false, loading from YAML will be skipped even if some YAML files were specified.
Definition param_provider.h:122
std::optional< std::string > prefix
If filled, overrides any prefix set using the setPrefix() method.
Definition param_provider.h:126
Helper struct for a numeric range with named members to make the code a bit more readable.
Definition param_provider.h:87
T maximum
Maximal value of a parameter.
Definition param_provider.h:91
T minimum
Minimal value of a parameter.
Definition param_provider.h:89
Definition param_provider.hpp:42
Struct of options when setting a parameter to ROS.
Definition param_provider.h:138
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:142
std::optional< std::string > prefix
If filled, overrides any prefix set using the setPrefix() method.
Definition param_provider.h:140