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 {
47
48 private:
49 enum unique_t
50 {
51 UNIQUE = true,
52 REUSABLE = false
53 };
54 enum optional_t
55 {
56 OPTIONAL = true,
57 COMPULSORY = false
58 };
59 enum swap_t
60 {
61 SWAP = true,
62 NO_SWAP = false
63 };
64
65 template <typename T>
66 using MatrixX = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
67
69
70 private:
71 bool m_load_successful, m_print_values;
72 std::string m_node_name;
73 std::shared_ptr<rclcpp::Node> m_node;
75 std::unordered_set<resolved_name_t> m_loaded_params;
76
77 /* printing helper functions //{ */
78
79 /* printError and printWarning functions //{*/
80
81 void printError(const std::string& str);
82 void printWarning(const std::string& str);
83
84 //}
85
86 /* printValue function and overloads //{ */
87
88 template <typename T>
89 void printValue(const resolved_name_t& name, const T& value) const;
90
91 //}
92
93 //}
94
95 /* loading helper functions //{ */
96
97 /* check_duplicit_loading checks whether the parameter was already loaded - returns true if yes //{ */
98
99 bool check_duplicit_loading(const resolved_name_t& name);
100
101 //}
102
103 /* helper functions for loading dynamic Eigen matrices //{ */
104 // loadMatrixX helper function for loading dynamic Eigen matrices //{
105 template <typename T>
106 std::pair<MatrixX<T>, bool> loadMatrixX(const std::string& name, const MatrixX<T>& default_value, int rows, int cols = Eigen::Dynamic,
107 optional_t optional = OPTIONAL, unique_t unique = UNIQUE, swap_t swap = NO_SWAP, bool printValues = true);
108 //}
109
110 /* loadMatrixStatic_internal helper function for loading static Eigen matrices //{ */
111 template <int rows, int cols, typename T>
112 std::pair<Eigen::Matrix<T, rows, cols>, bool> loadMatrixStatic_internal(const std::string& name, const Eigen::Matrix<T, rows, cols>& default_value,
113 optional_t optional, unique_t unique);
114 //}
115
116 /* loadMatrixKnown_internal helper function for loading EigenXd matrices with known dimensions //{ */
117 template <typename T>
118 std::pair<MatrixX<T>, bool> loadMatrixKnown_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional,
119 unique_t unique);
120 //}
121
122 /* loadMatrixDynamic_internal helper function for loading Eigen matrices with one dynamic (unspecified) dimension //{ */
123 template <typename T>
124 std::pair<MatrixX<T>, bool> loadMatrixDynamic_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional,
125 unique_t unique);
126 //}
127
128 /* loadMatrixArray_internal helper function for loading an array of EigenXd matrices with known dimensions //{ */
129 template <typename T>
130 std::vector<MatrixX<T>> loadMatrixArray_internal(const std::string& name, const std::vector<MatrixX<T>>& default_value, optional_t optional,
131 unique_t unique);
132 //}
133
134 //}
135
136 /* load helper function for generic types //{ */
137 // This function tries to load a parameter with name 'name' and a default value.
138 // You can use the flag 'optional' to not throw a ROS_ERROR when the parameter
139 // cannot be loaded and the flag 'printValues' to set whether the loaded
140 // value and name of the parameter should be printed to cout.
141 // If 'optional' is set to false and the parameter could not be loaded,
142 // the flag 'load_successful' is set to false and a ROS_ERROR message
143 // is printer.
144 // If 'unique' flag is set to false then the parameter is not checked
145 // for being loaded twice.
146 // Returns a tuple, containing either the loaded or the default value and a bool,
147 // indicating if the value was loaded (true) or the default value was used (false).
148 template <typename T>
149 std::pair<T, bool> load(const std::string& name, const T& default_value, optional_t optional = OPTIONAL, unique_t unique = UNIQUE);
150 //}
151 //}
152
153 public:
161 ParamLoader(const std::shared_ptr<rclcpp::Node>& node, bool printValues = true, std::string_view node_name = std::string());
162
163 /* Constructor overloads //{ */
170 ParamLoader(const std::shared_ptr<rclcpp::Node>& node, std::string node_name);
171
172 //}
173
174 /* setPrefix function //{ */
175
184 void setPrefix(const std::string& prefix);
185
186 //}
187
188 /* getPrefix function //{ */
189
195 std::string getPrefix();
196
197 //}
198
199 /* addYamlFile() function //{ */
200
207 bool addYamlFile(const std::string& filepath);
208 //}
209
210 /* addYamlFileFromParam() function //{ */
211
218 bool addYamlFileFromParam(const std::string& param_name);
219 //}
220
226 void copyYamls(const ParamLoader& param_loader);
227
234
235 /* loadedSuccessfully function //{ */
241 bool loadedSuccessfully() const;
242 //}
243
244 /* resetLoadedSuccessfully function //{ */
249 //}
250
251 /* resetUniques function //{ */
255 void resetUniques();
256 //}
257
258 /* loadParam function for optional parameters //{ */
271 template <typename T>
272 bool loadParam(const std::string& name, T& out_value, const T& default_value);
273
285 template <typename T>
286 T loadParam2(const std::string& name, const T& default_value);
287
300 template <typename T>
301 bool loadParamReusable(const std::string& name, T& out_value, const T& default_value);
302
314 template <typename T>
315 T loadParamReusable2(const std::string& name, const T& default_value);
316
317 //}
318
319 /* loadParam function for compulsory parameters //{ */
331 template <typename T>
332 bool loadParam(const std::string& name, T& out_value);
333
344 template <typename T>
345 T loadParam2(const std::string& name);
346
358 template <typename T>
359 bool loadParamReusable(const std::string& name, T& out_value);
360
371 template <typename T>
372 T loadParamReusable2(const std::string& name);
373
374 //}
375
376 /* loadParam specializations for rclcpp::Duration type //{ */
377
388 bool loadParam(const std::string& name, rclcpp::Duration& out, const rclcpp::Duration& default_value);
389
399 bool loadParam(const std::string& name, rclcpp::Duration& out);
400
401 //}
402
403 /* loadParam specializations for std_msgs::msg::ColorRGBA type //{ */
404
415 bool loadParam(const std::string& name, std_msgs::msg::ColorRGBA& out, const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
416
426 std_msgs::msg::ColorRGBA loadParam2(const std::string& name, const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
427
428 //}
429
430 /* loadParam specializations and convenience functions for Eigen dynamic matrix type //{ */
431
446 template <typename T>
447 bool loadParam(const std::string& name, MatrixX<T>& mat, const MatrixX<T>& default_value);
448
462 template <typename T>
463 MatrixX<T> loadParam2(const std::string& name, const MatrixX<T>& default_value);
464
465 //}
466
467 // loadMatrixStatic function for loading of static Eigen::Matrices //{
468
486 template <int rows, int cols, typename T>
487 bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat);
488
506 template <int rows, int cols, typename T, typename Derived>
507 bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat, const Eigen::MatrixBase<Derived>& default_value);
508
525 template <int rows, int cols, typename T = double>
526 Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name);
527
544 template <int rows, int cols, typename T, typename Derived>
545 Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value);
546
547 //}
548
549 // loadMatrixKnown function for loading of Eigen matrices with known dimensions //{
550
566 template <typename T>
567 bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, int rows, int cols);
568
584 template <typename T, typename Derived>
585 bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
586
601 template <typename T = double>
602 MatrixX<T> loadMatrixKnown2(const std::string& name, int rows, int cols);
603
618 template <typename T, typename Derived>
619 MatrixX<T> loadMatrixKnown2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
620
621 //}
622
623 // loadMatrixDynamic function for half-dynamic loading of MatrixX<T> //{
624
640 template <typename T>
641 bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, int rows, int cols);
642
659 template <typename T, typename Derived>
660 bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
661
676 template <typename T = double>
677 MatrixX<T> loadMatrixDynamic2(const std::string& name, int rows, int cols);
678
693 template <typename T, typename Derived>
694 MatrixX<T> loadMatrixDynamic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols);
695
696 //}
697
698 // loadMatrixArray function for loading of an array of MatrixX<T> with known dimensions //{
731 template <typename T>
732 void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat);
733
745 template <typename T>
746 void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat, const std::vector<MatrixX<T>>& default_value);
747
758 template <typename T = double>
759 std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name);
760
772 template <typename T>
773 std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name, const std::vector<MatrixX<T>>& default_value);
774
775 //}
776 };
777 //}
778
788 template <>
789 rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(const std::string& name, const rclcpp::Duration& default_value);
790
799 template <>
800 rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(const std::string& name);
801
802} // namespace mrs_lib
803
804#include <mrs_lib/impl/param_loader.hpp>
Convenience class for loading parameters from rosparam server.
Definition param_loader.h:46
void copyYamls(const ParamLoader &param_loader)
Copies parsed YAMLs from another ParamLoader.
Definition param_loader.cpp:136
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:603
void resetLoadedSuccessfully()
Resets the loadedSuccessfully flag back to true.
Definition param_loader.cpp:113
bool loadedSuccessfully() const
Indicates whether all compulsory parameters were successfully loaded.
Definition param_loader.cpp:108
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:840
bool addYamlFileFromParam(const std::string &param_name)
Loads a filepath from a parameter loads that file as a YAML.
Definition param_loader.cpp:128
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:807
std::string getPrefix()
Returns the current parameter name prefix.
Definition param_loader.cpp:103
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:322
bool addYamlFile(const std::string &filepath)
Adds the specified file as a source of static parameters.
Definition param_loader.cpp:123
void setPrefix(const std::string &prefix)
Sets a prefix that will be applied to parameter names before subnode namespaces.
Definition param_loader.cpp:98
Eigen::Matrix< T, rows, cols > loadMatrixStatic2(const std::string &name)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:553
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:304
bool loadMatrixStatic(const std::string &name, Eigen::Matrix< T, rows, cols > &mat)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:504
MatrixX< T > loadMatrixKnown2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory Eigen matrix parameters.
Definition param_loader.hpp:648
ParamProvider & getParamProvider()
Returns the internal ParamProvider object.
Definition param_loader.cpp:141
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:696
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:340
MatrixX< T > loadMatrixDynamic2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition param_loader.hpp:742
T loadParamReusable2(const std::string &name, const T &default_value)
Loads an optional reusable parameter from the rosparam server.
Definition param_loader.hpp:358
void resetUniques()
Resets the list of already loaded parameter names used when checking for uniqueness.
Definition param_loader.cpp:118
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:43