mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
param_provider.h
Go to the documentation of this file.
1// clang: MatousFormat
7#pragma once
8
9#include <concepts>
10#include <memory>
11#include <optional>
12
13#include <yaml-cpp/yaml.h>
14#include <rclcpp/rclcpp.hpp>
15
16namespace mrs_lib
17{
18
26 template <typename T>
27 std::ostream& operator<<(std::ostream& os, const std::vector<T>& var);
28
36 template <typename Key, typename Value>
37 std::ostream& operator<<(std::ostream& os, const std::map<Key, Value>& var);
38
46 std::ostream& operator<<(std::ostream& os, rclcpp::ParameterType& var);
47
53 template <typename T>
54 rclcpp::ParameterType to_param_type();
55
57 template <typename T>
58 concept numeric = (std::integral<T> || std::floating_point<T>) && !std::same_as<T, bool>;
59
60 /*** ParamProvider CLASS //{ **/
61
73 {
74 public:
82 struct resolved_name_t;
83
85 template <typename T>
86 struct range_t
87 {
92 };
93
100 template <typename T>
102 {
104 bool reconfigurable = false;
106 std::optional<T> default_value = std::nullopt;
108 std::optional<range_t<T>> range = std::nullopt;
109 };
110
116 template <typename T>
118 {
120 bool always_declare = false;
122 bool use_yaml = true;
124 std::optional<bool> use_rosparam = std::nullopt;
126 std::optional<std::string> prefix = std::nullopt;
129 };
130
132 enum class get_result_t
133 {
135 LOADED,
137 DEFAULT,
139 FAILED,
140 };
141
147 template <typename T>
149 {
151 std::optional<std::string> prefix = std::nullopt;
154 };
155
162 ParamProvider(const std::shared_ptr<rclcpp::Node>& node, const bool use_rosparam = true);
163
171 bool addYamlFile(const std::string& filepath);
172
178 void copyYamls(const ParamProvider& param_provider);
179
191 template <typename T>
192 bool getParam(const std::string& param_name, T& value_out) const;
193
206 template <typename T>
207 get_result_t getParamResult(const std::string& param_name, T& value_out, const get_options_t<T>& opts = {}) const;
208
221 template <typename T>
222 bool getParam(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts = {}) const;
223
236 template <typename T>
237 get_result_t getParamResult(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts = {}) const;
238
248 template <typename T>
249 bool setParam(const std::string& param_name, const T& value) const;
250
262 template <typename T>
263 bool setParam(const resolved_name_t& resolved_name, const T& value, const set_options_t<T>& opts = {}) const;
264
273 template <typename T>
274 bool declareParam(const std::string& param_name) const;
275
285 template <typename T>
286 bool declareParam(const std::string& param_name, const T& default_value) const;
287
298 template <typename T>
299 bool declareParam(const resolved_name_t& resolved_name, const declare_options_t<T>& opts = {}) const;
300
309 void setPrefix(const std::string& prefix);
310
316 std::string getPrefix() const;
317
324 resolved_name_t resolveName(const std::string& param_name) const;
325
326 private:
327 std::vector<std::shared_ptr<YAML::Node>> m_yamls;
328 std::shared_ptr<rclcpp::Node> m_node;
329 std::string m_node_name;
330 bool m_use_rosparam;
331 std::string m_prefix;
332
333 std::optional<YAML::Node> findYamlNode(const resolved_name_t& resolved_name) const;
334
335 template <typename T>
336 static inline T degrees2radians(const T degrees);
337
338 template <typename T>
339 T applyTag(const YAML::Node& node) const;
340
341 template <typename T>
342 bool ranges_match(const rcl_interfaces::msg::ParameterDescriptor& descriptor, const range_t<T>& declare_range) const;
343
344 template <typename T>
345 bool loadFromYaml(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts) const;
346
347 template <typename T>
348 bool loadFromROS(const resolved_name_t& resolved_name, T& value_out, const get_options_t<T>& opts) const;
349 };
350 //}
351
352} // namespace mrs_lib
353
354#ifndef PARAM_PROVIDER_HPP
356#endif
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:63
void setPrefix(const std::string &prefix)
Sets a prefix that will be applied to parameter names before subnode namespaces.
Definition param_provider.cpp:150
resolved_name_t resolveName(const std::string &param_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:160
bool getParam(const std::string &param_name, T &value_out) const
Gets the value of a parameter.
Definition param_provider.hpp:83
get_result_t
Explicit result state for parameter loading.
Definition param_provider.h:133
@ DEFAULT
Parameter value resolved using provided default value.
@ LOADED
Parameter value loaded from YAML/ROS.
@ FAILED
Parameter value could not be resolved.
std::string getPrefix() const
Returns the current parameter name prefix.
Definition param_provider.cpp:155
bool declareParam(const std::string &param_name) const
Defines a parameter.
Definition param_provider.hpp:188
get_result_t getParamResult(const std::string &param_name, T &value_out, const get_options_t< T > &opts={}) const
Gets the value of a parameter and returns an explicit result state.
Definition param_provider.hpp:89
bool setParam(const std::string &param_name, const T &value) const
Sets the value of a parameter to ROS.
Definition param_provider.hpp:146
void copyYamls(const ParamProvider &param_provider)
Copy parsed YAMLs from another ParamProvider.
Definition param_provider.cpp:93
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:75
Implements ParamProvider - a convenience class for seamlessly loading parameters from YAML or ROS.
Definition cyclic_example.cpp:23
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:43
Struct of options when setting a parameter to ROS.
Definition param_provider.h:149
declare_options_t< T > declare_options
Options when declaring a parameter to ROS (see the declare_options_t<T> documentation).
Definition param_provider.h:153
std::optional< std::string > prefix
If filled, overrides any prefix set using the setPrefix() method.
Definition param_provider.h:151