mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
param_loader.h
1// clang: MatousFormat
2#pragma once
3
4#include <rclcpp/rclcpp.hpp>
5#include <string>
6#include <unordered_set>
7#include <Eigen/Dense>
8#include <std_msgs/msg/color_rgba.hpp>
10
11namespace mrs_lib
12{
13
21 template <typename T>
22 std::ostream& operator<<(std::ostream& os, const Eigen::MatrixX<T>& var);
23
24/*** ParamLoader CLASS //{ **/
25
46
47private:
48 enum unique_t
49 {
50 UNIQUE = true,
51 REUSABLE = false
52 };
53 enum optional_t
54 {
55 OPTIONAL = true,
56 COMPULSORY = false
57 };
58 enum swap_t
59 {
60 SWAP = true,
61 NO_SWAP = false
62 };
63
64 template <typename T>
65 using MatrixX = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
66
68
69private:
70 bool m_load_successful, m_print_values;
71 std::string m_node_name;
72 std::shared_ptr<rclcpp::Node> m_node;
74 std::unordered_set<resolved_name_t> m_loaded_params;
75
76 /* printing helper functions //{ */
77
78 /* printError and printWarning functions //{*/
79
80 void printError(const std::string& str);
81 void printWarning(const std::string& str);
82
83 //}
84
85 /* printValue function and overloads //{ */
86
87 template <typename T>
88 void printValue(const resolved_name_t& name, const T& value) const;
89
90 //}
91
92 //}
93
94 /* loading helper functions //{ */
95
96 /* check_duplicit_loading checks whether the parameter was already loaded - returns true if yes //{ */
97
98 bool check_duplicit_loading(const resolved_name_t& name);
99
100 //}
101
102 /* helper functions for loading dynamic Eigen matrices //{ */
103 // loadMatrixX helper function for loading dynamic Eigen matrices //{
104 template <typename T>
105 std::pair<MatrixX<T>, bool> loadMatrixX(const std::string& name, const MatrixX<T>& default_value, int rows, int cols = Eigen::Dynamic, optional_t optional = OPTIONAL, unique_t unique = UNIQUE, swap_t swap = NO_SWAP, bool printValues = true);
106 //}
107
108 /* loadMatrixStatic_internal helper function for loading static Eigen matrices //{ */
109 template <int rows, int cols, typename T>
110 std::pair<Eigen::Matrix<T, rows, cols>, bool> loadMatrixStatic_internal(const std::string& name, const Eigen::Matrix<T, rows, cols>& default_value, optional_t optional, unique_t unique);
111 //}
112
113 /* loadMatrixKnown_internal helper function for loading EigenXd matrices with known dimensions //{ */
114 template <typename T>
115 std::pair<MatrixX<T>, bool> loadMatrixKnown_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional, unique_t unique);
116 //}
117
118 /* loadMatrixDynamic_internal helper function for loading Eigen matrices with one dynamic (unspecified) dimension //{ */
119 template <typename T>
120 std::pair<MatrixX<T>, bool> loadMatrixDynamic_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional, unique_t unique);
121 //}
122
123 /* loadMatrixArray_internal helper function for loading an array of EigenXd matrices with known dimensions //{ */
124 template <typename T>
125 std::vector<MatrixX<T>> loadMatrixArray_internal(const std::string& name, const std::vector<MatrixX<T>>& default_value, optional_t optional, unique_t unique);
126 //}
127
128 //}
129
130 /* load helper function for generic types //{ */
131 // This function tries to load a parameter with name 'name' and a default value.
132 // You can use the flag 'optional' to not throw a ROS_ERROR when the parameter
133 // cannot be loaded and the flag 'printValues' to set whether the loaded
134 // value and name of the parameter should be printed to cout.
135 // If 'optional' is set to false and the parameter could not be loaded,
136 // the flag 'load_successful' is set to false and a ROS_ERROR message
137 // is printer.
138 // If 'unique' flag is set to false then the parameter is not checked
139 // for being loaded twice.
140 // Returns a tuple, containing either the loaded or the default value and a bool,
141 // indicating if the value was loaded (true) or the default value was used (false).
142 template <typename T>
143 std::pair<T, bool> load(const std::string& name, const T& default_value, optional_t optional = OPTIONAL, unique_t unique = UNIQUE);
144 //}
145 //}
146
147public:
155 ParamLoader(const std::shared_ptr<rclcpp::Node>& node, bool printValues = true, std::string_view node_name = std::string());
156
157 /* Constructor overloads //{ */
164 ParamLoader(const std::shared_ptr<rclcpp::Node>& node, std::string node_name);
165
166 //}
167
168 /* setPrefix function //{ */
169
178 void setPrefix(const std::string& prefix);
179
180 //}
181
182 /* getPrefix function //{ */
183
189 std::string getPrefix();
190
191 //}
192
193 /* addYamlFile() function //{ */
194
201 bool addYamlFile(const std::string& filepath);
202 //}
203
204 /* addYamlFileFromParam() function //{ */
205
212 bool addYamlFileFromParam(const std::string& param_name);
213 //}
214
220 void copyYamls(const ParamLoader& param_loader);
221
228
229 /* loadedSuccessfully function //{ */
235 bool loadedSuccessfully() const;
236 //}
237
238 /* resetLoadedSuccessfully function //{ */
243 //}
244
245 /* resetUniques function //{ */
249 void resetUniques();
250 //}
251
252 /* loadParam function for optional parameters //{ */
265 template <typename T>
266 bool loadParam(const std::string& name, T& out_value, const T& default_value);
267
279 template <typename T>
280 T loadParam2(const std::string& name, const T& default_value);
281
294 template <typename T>
295 bool loadParamReusable(const std::string& name, T& out_value, const T& default_value);
296
308 template <typename T>
309 T loadParamReusable2(const std::string& name, const T& default_value);
310
311 //}
312
313 /* loadParam function for compulsory parameters //{ */
325 template <typename T>
326 bool loadParam(const std::string& name, T& out_value);
327
338 template <typename T>
339 T loadParam2(const std::string& name);
340
352 template <typename T>
353 bool loadParamReusable(const std::string& name, T& out_value);
354
365 template <typename T>
366 T loadParamReusable2(const std::string& name);
367
368 //}
369
370 /* loadParam specializations for rclcpp::Duration type //{ */
371
382 bool loadParam(const std::string& name, rclcpp::Duration& out, const rclcpp::Duration& default_value);
383
393 bool loadParam(const std::string& name, rclcpp::Duration& out);
394
395 //}
396
397 /* loadParam specializations for std_msgs::msg::ColorRGBA type //{ */
398
409 bool loadParam(const std::string& name, std_msgs::msg::ColorRGBA& out, const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
410
420 std_msgs::msg::ColorRGBA loadParam2(const std::string& name, const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
421
422 //}
423
424 /* loadParam specializations and convenience functions for Eigen dynamic matrix type //{ */
425
440 template <typename T>
441 bool loadParam(const std::string& name, MatrixX<T>& mat, const MatrixX<T>& default_value);
442
456 template <typename T>
457 MatrixX<T> loadParam2(const std::string& name, const MatrixX<T>& default_value);
458
459 //}
460
461 // loadMatrixStatic function for loading of static Eigen::Matrices //{
462
480 template <int rows, int cols, typename T>
481 bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat);
482
500 template <int rows, int cols, typename T, typename Derived>
501 bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat, const Eigen::MatrixBase<Derived>& default_value);
502
519 template <int rows, int cols, typename T = double>
520 Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name);
521
538 template <int rows, int cols, typename T, typename Derived>
539 Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value);
540
541 //}
542
543 // loadMatrixKnown function for loading of Eigen matrices with known dimensions //{
544
560 template <typename T>
561 bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, int rows, int cols);
562
578 template <typename T, typename Derived>
579 bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
580
595 template <typename T = double>
596 MatrixX<T> loadMatrixKnown2(const std::string& name, int rows, int cols);
597
612 template <typename T, typename Derived>
613 MatrixX<T> loadMatrixKnown2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
614
615 //}
616
617 // loadMatrixDynamic function for half-dynamic loading of MatrixX<T> //{
618
634 template <typename T>
635 bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, int rows, int cols);
636
653 template <typename T, typename Derived>
654 bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
655
670 template <typename T = double>
671 MatrixX<T> loadMatrixDynamic2(const std::string& name, int rows, int cols);
672
687 template <typename T, typename Derived>
688 MatrixX<T> loadMatrixDynamic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
689
690 //}
691
692 // loadMatrixArray function for loading of an array of MatrixX<T> with known dimensions //{
725 template <typename T>
726 void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat);
727
739 template <typename T>
740 void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat, const std::vector<MatrixX<T>>& default_value);
741
752 template <typename T = double>
753 std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name);
754
766 template <typename T>
767 std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name, const std::vector<MatrixX<T>>& default_value);
768
769 //}
770
771};
772//}
773
783template <>
784rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(const std::string& name, const rclcpp::Duration& default_value);
785
794template <>
795rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(const std::string& name);
796
797} // namespace mrs_lib
798
799#include <mrs_lib/impl/param_loader.hpp>
Convenience class for loading parameters from rosparam server.
Definition param_loader.h:45
void copyYamls(const ParamLoader &param_loader)
Copies parsed YAMLs from another ParamLoader.
Definition param_loader.cpp:135
bool loadMatrixKnown(const std::string &name, MatrixX< T > &mat, int rows, int cols)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:576
void resetLoadedSuccessfully()
Resets the loadedSuccessfully flag back to true.
Definition param_loader.cpp:112
bool loadedSuccessfully() const
Indicates whether all compulsory parameters were successfully loaded.
Definition param_loader.cpp:107
std::vector< MatrixX< T > > loadMatrixArray2(const std::string &name)
Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matric...
Definition param_loader.hpp:813
bool addYamlFileFromParam(const std::string &param_name)
Loads a filepath from a parameter loads that file as a YAML.
Definition param_loader.cpp:127
void loadMatrixArray(const std::string &name, std::vector< MatrixX< T > > &mat)
Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matric...
Definition param_loader.hpp:780
std::string getPrefix()
Returns the current parameter name prefix.
Definition param_loader.cpp:102
T loadParam2(const std::string &name, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition param_loader.hpp:295
bool addYamlFile(const std::string &filepath)
Adds the specified file as a source of static parameters.
Definition param_loader.cpp:122
void setPrefix(const std::string &prefix)
Sets a prefix that will be applied to parameter names before subnode namespaces.
Definition param_loader.cpp:97
Eigen::Matrix< T, rows, cols > loadMatrixStatic2(const std::string &name)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:526
bool loadParam(const std::string &name, T &out_value, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition param_loader.hpp:277
bool loadMatrixStatic(const std::string &name, Eigen::Matrix< T, rows, cols > &mat)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:477
MatrixX< T > loadMatrixKnown2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:621
ParamProvider & getParamProvider()
Returns the internal ParamProvider object.
Definition param_loader.cpp:140
bool loadMatrixDynamic(const std::string &name, MatrixX< T > &mat, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition param_loader.hpp:669
bool loadParamReusable(const std::string &name, T &out_value, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition param_loader.hpp:313
MatrixX< T > loadMatrixDynamic2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition param_loader.hpp:715
T loadParamReusable2(const std::string &name, const T &default_value)
Loads an optional reusable parameter from the rosparam server.
Definition param_loader.hpp:331
void resetUniques()
Resets the list of already loaded parameter names used when checking for uniqueness.
Definition param_loader.cpp:117
Helper class for ParamLoader and DynparamMgr.
Definition param_provider.h:73
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
Defines ParamProvider - a convenience class for seamlessly loading parameters from YAML or ROS.
Definition param_provider.hpp:42