mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
param_loader.hpp
1// clang: MatousFormat
2#pragma once
3
4#include <mrs_lib/param_loader.h>
5
6namespace mrs_lib
7{
8
9 /* printValue function and overloads //{ */
10
11 template <typename T>
12 void ParamLoader::printValue(const resolved_name_t& name, const T& value) const
13 {
14 if (m_node_name.empty())
15 std::cout << "\t" << name << ":\t" << value << std::endl;
16 else
17 RCLCPP_INFO_STREAM(m_node->get_logger(), "[" << m_node_name << "]: parameter '" << name << "':\t" << value);
18 }
19
20 template <typename T>
21 std::ostream& operator<<(std::ostream& os, const Eigen::MatrixX<T>& var)
22 {
23 /* const Eigen::IOFormat fmt(4, 0, ", ", "\n", "\t\t[", "]"); */
24 /* strstr << value.format(fmt); */
25 const Eigen::IOFormat fmt;
26 return os << var.format(fmt);
27 }
28 //}
29
30 /* loading helper functions //{ */
31
32 /* helper functions for loading dynamic Eigen matrices //{ */
33 // loadMatrixX helper function for loading dynamic Eigen matrices //{
34 template <typename T>
35 std::pair<ParamLoader::MatrixX<T>, bool> ParamLoader::loadMatrixX(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional, unique_t unique, swap_t swap, bool printValues)
36 {
37 const auto resolved_name = m_pp.resolveName(name);
38 MatrixX<T> loaded = default_value;
39 bool used_rosparam_value = false;
40 // first, check if the user already tried to load this parameter
41 if (unique && check_duplicit_loading(resolved_name))
42 return {loaded, used_rosparam_value};
43
44 // this function only accepts dynamic columns (you can always transpose the matrix afterward)
45 if (rows < 0) {
46 // if the parameter was compulsory, alert the user and set the flag
47 printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved_name.str);
48 m_load_successful = false;
49 return {loaded, used_rosparam_value};
50 }
51 const bool expect_zero_matrix = rows == 0;
52 if (expect_zero_matrix) {
53 if (cols > 0) {
54 printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved_name.str +
55 ". One dimension indicates zero matrix, but other expects non-zero.");
56 m_load_successful = false;
57 return {loaded, used_rosparam_value};
58 }
59 }
60
61 bool cur_load_successful = true;
62 bool check_size_exact = true;
63 if (cols <= 0) // this means that the cols dimension is dynamic or a zero matrix is expected
64 check_size_exact = false;
65
66 std::vector<T> tmp_vec;
67 // try to load the parameter
68 const bool success = m_pp.getParam(resolved_name, tmp_vec);
69 // check if the loaded vector has correct length
70 bool correct_size = (int)tmp_vec.size() == rows * cols;
71 if (!check_size_exact && !expect_zero_matrix)
72 correct_size = (int)tmp_vec.size() % rows == 0; // if the cols dimension is dynamic, the size just has to be divisable by rows
73
74 if (success && correct_size) {
75 // if successfully loaded, everything is in order
76 // transform the vector to the matrix
77 if (cols <= 0 && rows > 0)
78 cols = tmp_vec.size() / rows;
79 if (swap)
80 std::swap(rows, cols);
81 loaded = Eigen::Map<Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>, Eigen::Unaligned>(tmp_vec.data(), rows, cols);
82 used_rosparam_value = true;
83 } else {
84 if (success && !correct_size) {
85 // warn the user that this parameter was not successfully loaded because of wrong vector length (might be an oversight)
86 std::string warning =
87 std::string("Matrix parameter ") + resolved_name.str +
88 std::string(" could not be loaded because the vector has a wrong length " + std::to_string(tmp_vec.size()) + " instead of expected ");
89 // process the message correctly based on whether the loaded matrix should be dynamic or static
90 if (cols <= 0) // for dynamic matrices
91 warning = warning + std::string("number divisible by ") + std::to_string(rows);
92 else // for static matrices
93 warning = warning + std::to_string(rows * cols);
94 printWarning(warning);
95 }
96 // if it was not loaded, the default value is used (set at the beginning of the function)
97 if (!optional) {
98 // if the parameter was compulsory, alert the user and set the flag
99 printError(std::string("Could not load non-optional parameter ") + resolved_name.str);
100 cur_load_successful = false;
101 }
102 }
103
104 // check if load was a success
105 if (cur_load_successful) {
106 if (m_print_values && printValues)
107 printValue(resolved_name, loaded);
108 m_loaded_params.insert(resolved_name);
109 } else {
110 m_load_successful = false;
111 }
112 // finally, return the resulting value
113 return {loaded, used_rosparam_value};
114 }
115 //}
116
117 /* loadMatrixStatic_internal helper function for loading static Eigen matrices //{ */
118 template <int rows, int cols, typename T>
119 std::pair<Eigen::Matrix<T, rows, cols>, bool> ParamLoader::loadMatrixStatic_internal(const std::string& name, const Eigen::Matrix<T, rows, cols>& default_value, optional_t optional, unique_t unique)
120 {
121 const auto [dynamic, loaded_ok] = loadMatrixX(name, MatrixX<T>(default_value), rows, cols, optional, unique, NO_SWAP);
122 return {dynamic, loaded_ok};
123 }
124 //}
125
126 /* loadMatrixKnown_internal helper function for loading EigenXd matrices with known dimensions //{ */
127 template <typename T>
128 std::pair<ParamLoader::MatrixX<T>, bool> ParamLoader::loadMatrixKnown_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional, unique_t unique)
129 {
130 MatrixX<T> loaded = default_value;
131 // first, check that at least one dimension is set
132 if (rows <= 0 || cols <= 0) {
133 printError(std::string("Invalid expected matrix dimensions for parameter ") + m_pp.resolveName(name).str + std::string(" (use loadMatrixDynamic?)"));
134 m_load_successful = false;
135 return {loaded, false};
136 }
137
138 return loadMatrixX(name, default_value, rows, cols, optional, unique, NO_SWAP);
139 }
140 //}
141
142 /* loadMatrixDynamic_internal helper function for loading Eigen matrices with one dynamic (unspecified) dimension //{ */
143 template <typename T>
144 std::pair<ParamLoader::MatrixX<T>, bool> ParamLoader::loadMatrixDynamic_internal(const std::string& name, const MatrixX<T>& default_value, int rows, int cols, optional_t optional, unique_t unique)
145 {
146 MatrixX<T> loaded = default_value;
147
148 // next, check that at least one dimension is set
149 if (rows <= 0 && cols <= 0) {
150 printError(std::string("Invalid expected matrix dimensions for parameter ") + m_pp.resolveName(name).str +
151 std::string(" (at least one dimension must be specified)"));
152 m_load_successful = false;
153 return {loaded, false};
154 }
155
156 swap_t swap = NO_SWAP;
157 if (rows <= 0) {
158 std::swap(rows, cols);
159 swap = SWAP;
160 }
161 return loadMatrixX(name, default_value, rows, cols, optional, unique, swap);
162 }
163 //}
164
165 /* loadMatrixArray_internal helper function for loading an array of EigenXd matrices with known dimensions //{ */
166 template <typename T>
167 std::vector<ParamLoader::MatrixX<T>> ParamLoader::loadMatrixArray_internal(const std::string& name, const std::vector<MatrixX<T>>& default_value, optional_t optional, unique_t unique)
168 {
169 const auto resolved_name = m_pp.resolveName(name);
170 int rows;
171 std::vector<long int> cols;
172 bool success = true;
173 success = success && m_pp.getParam(resolved_name_t(resolved_name.str + "/rows"), rows);
174 success = success && m_pp.getParam(resolved_name_t(resolved_name.str + "/cols"), cols);
175
176 std::vector<MatrixX<T>> loaded;
177 loaded.reserve(cols.size());
178
179 int total_cols = 0;
180 /* check correctness of loaded parameters so far calculate the total dimension //{ */
181
182 if (!success) {
183 printError(std::string("Failed to load ") + resolved_name.str + std::string("/rows or ") + resolved_name.str + std::string("/cols"));
184 m_load_successful = false;
185 return default_value;
186 }
187 if (rows < 0) {
188 printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved_name.str + std::string(" (rows and cols must be >= 0)"));
189 m_load_successful = false;
190 return default_value;
191 }
192 for (const auto& col : cols) {
193 if (col < 0) {
194 printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved_name.str + std::string(" (rows and cols must be >= 0)"));
195 m_load_successful = false;
196 return default_value;
197 }
198 total_cols += col;
199 }
200
201 //}
202
203 const auto [loaded_matrix, loaded_ok] = loadMatrixX(name + "/data", MatrixX<T>(), rows, total_cols, optional, unique, NO_SWAP, false);
204 /* std::cout << "loaded_matrix: " << loaded_matrix << std::endl; */
205 /* std::cout << "loaded_matrix: " << loaded_matrix.rows() << "x" << loaded_matrix.cols() << std::endl; */
206 /* std::cout << "expected dims: " << rows << "x" << total_cols << std::endl; */
207 if (loaded_matrix.rows() != rows || loaded_matrix.cols() != total_cols) {
208 m_load_successful = false;
209 return default_value;
210 }
211
212 int cols_loaded = 0;
213 for (unsigned it = 0; it < cols.size(); it++) {
214 const int cur_cols = cols.at(it);
215 const MatrixX<T> cur_mat = loaded_matrix.block(0, cols_loaded, rows, cur_cols);
216 /* std::cout << "cur_mat: " << cur_mat << std::endl; */
217 loaded.push_back(cur_mat);
218 cols_loaded += cur_cols;
219 printValue(resolved_name_t(resolved_name.str + "/matrix#" + std::to_string(it)), cur_mat);
220 }
221 return loaded;
222 }
223 //}
224
225 //}
226
227 /* load helper function for generic types //{ */
228 // This function tries to load a parameter with name 'name' and a default value.
229 // You can use the flag 'optional' to not throw a ROS_ERROR when the parameter
230 // cannot be loaded and the flag 'printValues' to set whether the loaded
231 // value and name of the parameter should be printed to cout.
232 // If 'optional' is set to false and the parameter could not be loaded,
233 // the flag 'load_successful' is set to false and a ROS_ERROR message
234 // is printer.
235 // If 'unique' flag is set to false then the parameter is not checked
236 // for being loaded twice.
237 // Returns a tuple, containing either the loaded or the default value and a bool,
238 // indicating if the value was loaded (true) or the default value was used (false).
239 template <typename T>
240 std::pair<T, bool> ParamLoader::load(const std::string& name, const T& default_value, optional_t optional, unique_t unique)
241 {
242 const auto resolved_name = m_pp.resolveName(name);
243 T loaded = default_value;
244 if (unique && check_duplicit_loading(resolved_name))
245 return {loaded, false};
246
247 bool cur_load_successful = true;
248 // try to load the parameter
249 const bool success = m_pp.getParam(resolved_name, loaded);
250 if (!success) {
251 // if it was not loaded, set the default value
252 loaded = default_value;
253 if (!optional) {
254 // if the parameter was compulsory, alert the user and set the flag
255 printError(std::string("Could not load non-optional parameter ") + resolved_name.str);
256 cur_load_successful = false;
257 }
258 }
259
260 if (cur_load_successful) {
261 // everything is fine and just print the resolved_name and value if required
262 if (m_print_values)
263 printValue(resolved_name, loaded);
264 // mark the param resolved_name as successfully loaded
265 m_loaded_params.insert(resolved_name);
266 } else {
267 m_load_successful = false;
268 }
269 // finally, return the resulting value
270 return {loaded, success};
271 }
272 //}
273 //}
274
275 /* loadParam function for optional parameters //{ */
276 template <typename T>
277 bool ParamLoader::loadParam(const std::string& name, T& out_value, const T& default_value)
278 {
279 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, UNIQUE);
280 out_value = ret;
281 return success;
282 }
294 template <typename T>
295 T ParamLoader::loadParam2(const std::string& name, const T& default_value)
296 {
297 const auto loaded = load<T>(name, default_value, OPTIONAL, UNIQUE);
298 return loaded.first;
299 }
312 template <typename T>
313 bool ParamLoader::loadParamReusable(const std::string& name, T& out_value, const T& default_value)
314 {
315 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
316 out_value = ret;
317 return success;
318 }
330 template <typename T>
331 T ParamLoader::loadParamReusable2(const std::string& name, const T& default_value)
332 {
333 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
334 return ret;
335 }
336 //}
337
338 /* loadParam function for compulsory parameters //{ */
350 template <typename T>
351 bool ParamLoader::loadParam(const std::string& name, T& out_value)
352 {
353 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
354 out_value = ret;
355 return success;
356 }
367 template <typename T>
368 T ParamLoader::loadParam2(const std::string& name)
369 {
370 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
371 return ret;
372 }
384 template <typename T>
385 bool ParamLoader::loadParamReusable(const std::string& name, T& out_value)
386 {
387 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
388 out_value = ret;
389 return success;
390 }
401 template <typename T>
402 T ParamLoader::loadParamReusable2(const std::string& name)
403 {
404 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
405 return ret;
406 }
407 //}
408
409 /* loadParam specializations and convenience functions for Eigen dynamic matrix type //{ */
410
425 template <typename T>
426 bool ParamLoader::loadParam(const std::string& name, MatrixX<T>& mat, const MatrixX<T>& default_value)
427 {
428 const int rows = default_value.rows();
429 const int cols = default_value.cols();
430 const bool loaded_ok = loadMatrixDynamic(name, mat, default_value, rows, cols);
431 return loaded_ok;
432 }
433
447 template <typename T>
448 ParamLoader::MatrixX<T> ParamLoader::loadParam2(const std::string& name, const MatrixX<T>& default_value)
449 {
450 MatrixX<T> ret;
451 loadParam(name, ret, default_value);
452 return ret;
453 }
454
455 //}
456
457 // loadMatrixStatic function for loading of static Eigen::Matrices //{
458
476 template <int rows, int cols, typename T>
477 bool ParamLoader::loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat)
478 {
479 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>::Zero(), COMPULSORY, UNIQUE);
480 mat = ret;
481 return loaded_ok;
482 }
483
501 template <int rows, int cols, typename T, typename Derived>
502 bool ParamLoader::loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat, const Eigen::MatrixBase<Derived>& default_value)
503 {
504 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>(default_value), OPTIONAL, UNIQUE);
505 mat = ret;
506 return loaded_ok;
507 }
508
525 template <int rows, int cols, typename T>
526 Eigen::Matrix<T, rows, cols> ParamLoader::loadMatrixStatic2(const std::string& name)
527 {
528 Eigen::Matrix<T, rows, cols> ret;
529 loadMatrixStatic(name, ret);
530 return ret;
531 }
532
549 template <int rows, int cols, typename T, typename Derived>
550 Eigen::Matrix<T, rows, cols> ParamLoader::loadMatrixStatic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value)
551 {
552 Eigen::Matrix<T, rows, cols> ret;
553 loadMatrixStatic(name, ret, default_value);
554 return ret;
555 }
556 //}
557
558 // loadMatrixKnown function for loading of Eigen matrices with known dimensions //{
559
575 template <typename T>
576 bool ParamLoader::loadMatrixKnown(const std::string& name, MatrixX<T>& mat, int rows, int cols)
577 {
578 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
579 mat = ret;
580 return loaded_ok;
581 }
582
598 template <typename T, typename Derived>
599 bool ParamLoader::loadMatrixKnown(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
600 {
601 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
602 mat = ret;
603 return loaded_ok;
604 }
605
620 template <typename T>
621 ParamLoader::MatrixX<T> ParamLoader::loadMatrixKnown2(const std::string& name, int rows, int cols)
622 {
623 MatrixX<T> ret;
624 loadMatrixKnown(name, ret, rows, cols);
625 return ret;
626 }
627
642 template <typename T, typename Derived>
643 ParamLoader::MatrixX<T> ParamLoader::loadMatrixKnown2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
644 {
645 MatrixX<T> ret;
646 loadMatrixKnown(name, ret, default_value, rows, cols);
647 return ret;
648 }
649 //}
650
651 // loadMatrixDynamic function for half-dynamic loading of MatrixX<T> //{
652
668 template <typename T>
669 bool ParamLoader::loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, int rows, int cols)
670 {
671 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
672 mat = ret;
673 return loaded_ok;
674 }
675
692 template <typename T, typename Derived>
693 bool ParamLoader::loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
694 {
695 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
696 mat = ret;
697 return loaded_ok;
698 }
699
714 template <typename T>
715 ParamLoader::MatrixX<T> ParamLoader::loadMatrixDynamic2(const std::string& name, int rows, int cols)
716 {
717 MatrixX<T> ret;
718 loadMatrixDynamic(name, ret, rows, cols);
719 return ret;
720 }
721
736 template <typename T, typename Derived>
737 ParamLoader::MatrixX<T> ParamLoader::loadMatrixDynamic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
738 {
739 MatrixX<T> ret;
740 loadMatrixDynamic(name, ret, default_value, rows, cols);
741 return ret;
742 }
743
744 //}
745
746 // loadMatrixArray function for loading of an array of MatrixX<T> with known dimensions //{
779 template <typename T>
780 void ParamLoader::loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat)
781 {
782 mat = loadMatrixArray2<double>(name);
783 }
784
796 template <typename T>
797 void ParamLoader::loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat, const std::vector<MatrixX<T>>& default_value)
798 {
799 mat = loadMatrixArray2(name, default_value);
800 }
801
812 template <typename T>
813 std::vector<ParamLoader::MatrixX<T>> ParamLoader::loadMatrixArray2(const std::string& name)
814 {
815 return loadMatrixArray_internal(name, std::vector<MatrixX<T>>(), COMPULSORY, UNIQUE);
816 }
817
829 template <typename T>
830 std::vector<ParamLoader::MatrixX<T>> ParamLoader::loadMatrixArray2(const std::string& name, const std::vector<MatrixX<T>>& default_value)
831 {
832 return loadMatrixArray_internal(name, default_value, OPTIONAL, UNIQUE);
833 }
834 //}
835
836} // namespace mrs_lib
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
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
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
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
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
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
resolved_name_t resolveName(const std::string &param_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:148
bool getParam(const std::string &param_name, T &value_out) const
Gets the value of a parameter.
Definition param_provider.hpp:78
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