mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
param_loader.h
Go to the documentation of this file.
1 // clang: MatousFormat
7 #ifndef PARAM_LOADER_H
8 #define PARAM_LOADER_H
9 
10 #include <ros/ros.h>
11 #include <string>
12 #include <map>
13 #include <unordered_set>
14 #include <iostream>
15 #include <Eigen/Dense>
16 #include <std_msgs/ColorRGBA.h>
17 #include <mrs_lib/param_provider.h>
18 
19 namespace mrs_lib
20 {
21 
22 /*** ParamLoader CLASS //{ **/
23 
44 {
45 
46 private:
47  enum unique_t
48  {
49  UNIQUE = true,
50  REUSABLE = false
51  };
52  enum optional_t
53  {
54  OPTIONAL = true,
55  COMPULSORY = false
56  };
57  enum swap_t
58  {
59  SWAP = true,
60  NO_SWAP = false
61  };
62 
63  template <typename T>
64  using MatrixX = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
65 
66 private:
67  bool m_load_successful, m_print_values;
68  std::string m_node_name;
69  std::string m_prefix;
70  const ros::NodeHandle& m_nh;
72  std::unordered_set<std::string> m_loaded_params;
73 
74  /* printing helper functions //{ */
75  /* printError and print_warning functions //{*/
76  void printError(const std::string& str)
77  {
78  if (m_node_name.empty())
79  ROS_ERROR_STREAM(str);
80  else
81  ROS_ERROR_STREAM("[" << m_node_name << "]: " << str);
82  }
83  void print_warning(const std::string& str)
84  {
85  if (m_node_name.empty())
86  ROS_WARN_STREAM(str);
87  else
88  ROS_WARN_STREAM("[" << m_node_name << "]: " << str);
89  }
90  //}
91 
92  /* printValue function and overloads //{ */
93 
94  template <typename T>
95  void printValue(const std::string& name, const T& value)
96  {
97  if (m_node_name.empty())
98  std::cout << "\t" << name << ":\t" << value << std::endl;
99  else
100  ROS_INFO_STREAM("[" << m_node_name << "]: parameter '" << name << "':\t" << value);
101  }
102 
103  template <typename T>
104  void printValue(const std::string& name, const std::vector<T>& value)
105  {
106  std::stringstream strstr;
107  if (m_node_name.empty())
108  strstr << "\t";
109  strstr << name << ":\t";
110  size_t it = 0;
111  for (const auto& elem : value)
112  {
113  strstr << elem;
114  if (it < value.size() - 1)
115  strstr << ", ";
116  it++;
117  }
118  if (m_node_name.empty())
119  std::cout << strstr.str() << std::endl;
120  else
121  ROS_INFO_STREAM("[" << m_node_name << "]: parameter '" << strstr.str());
122  }
123 
124  template <typename T1, typename T2>
125  void printValue(const std::string& name, const std::map<T1, T2>& value)
126  {
127  std::stringstream strstr;
128  if (m_node_name.empty())
129  strstr << "\t";
130  strstr << name << ":" << std::endl;
131  size_t it = 0;
132  for (const auto& pair : value)
133  {
134  strstr << pair.first << " = " << pair.second;
135  if (it < value.size() - 1)
136  strstr << std::endl;
137  it++;
138  }
139  if (m_node_name.empty())
140  std::cout << strstr.str() << std::endl;
141  else
142  ROS_INFO_STREAM("[" << m_node_name << "]: parameter '" << strstr.str());
143  }
144 
145  template <typename T>
146  void printValue(const std::string& name, const MatrixX<T>& value)
147  {
148  std::stringstream strstr;
149  /* const Eigen::IOFormat fmt(4, 0, ", ", "\n", "\t\t[", "]"); */
150  /* strstr << value.format(fmt); */
151  const Eigen::IOFormat fmt;
152  strstr << value.format(fmt);
153  if (m_node_name.empty())
154  std::cout << "\t" << name << ":\t" << std::endl << strstr.str() << std::endl;
155  else
156  ROS_INFO_STREAM("[" << m_node_name << "]: parameter '" << name << "':" << std::endl << strstr.str());
157  }
158 
159  std::string printValue_recursive(const std::string& name, XmlRpc::XmlRpcValue& value, unsigned depth = 0)
160  {
161  std::stringstream strstr;
162  for (unsigned it = 0; it < depth; it++)
163  strstr << "\t";
164  strstr << name << ":";
165  switch (value.getType())
166  {
167  case XmlRpc::XmlRpcValue::TypeArray:
168  {
169  for (int it = 0; it < value.size(); it++)
170  {
171  strstr << std::endl;
172  const std::string name = "[" + std::to_string(it) + "]";
173  strstr << printValue_recursive(name, value[it], depth+1);
174  }
175  break;
176  }
177  case XmlRpc::XmlRpcValue::TypeStruct:
178  {
179  int it = 0;
180  for (auto& pair : value)
181  {
182  strstr << std::endl;
183  strstr << printValue_recursive(pair.first, pair.second, depth+1);
184  it++;
185  }
186  break;
187  }
188  default:
189  {
190  strstr << "\t" << value;
191  break;
192  }
193  }
194  return strstr.str();
195  }
196 
197  void printValue(const std::string& name, XmlRpc::XmlRpcValue& value)
198  {
199  const std::string txt = printValue_recursive(name, value);
200  if (m_node_name.empty())
201  std::cout << txt << std::endl;
202  else
203  ROS_INFO_STREAM("[" << m_node_name << "]: parameter '" << txt);
204  }
205 
206  //}
207 
208  std::string resolved(const std::string& param_name)
209  {
210  return m_nh.resolveName(param_name);
211  }
212  //}
213 
214  /* check_duplicit_loading checks whether the parameter was already loaded - returns true if yes //{ */
215  bool check_duplicit_loading(const std::string& name)
216  {
217  if (m_loaded_params.count(name))
218  {
219  printError(std::string("Tried to load parameter ") + name + std::string(" twice"));
220  m_load_successful = false;
221  return true;
222  } else
223  {
224  return false;
225  }
226  }
227  //}
228 
229  /* helper functions for loading dynamic Eigen matrices //{ */
230  // loadMatrixX helper function for loading dynamic Eigen matrices //{
231  template <typename T>
232  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)
233  {
234  const std::string name_prefixed = m_prefix + name;
235  MatrixX<T> loaded = default_value;
236  bool used_rosparam_value = false;
237  // first, check if the user already tried to load this parameter
238  if (unique && check_duplicit_loading(name_prefixed))
239  return {loaded, used_rosparam_value};
240 
241  // this function only accepts dynamic columns (you can always transpose the matrix afterward)
242  if (rows < 0)
243  {
244  // if the parameter was compulsory, alert the user and set the flag
245  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name_prefixed));
246  m_load_successful = false;
247  return {loaded, used_rosparam_value};
248  }
249  const bool expect_zero_matrix = rows == 0;
250  if (expect_zero_matrix)
251  {
252  if (cols > 0)
253  {
254  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name_prefixed) + ". One dimension indicates zero matrix, but other expects non-zero.");
255  m_load_successful = false;
256  return {loaded, used_rosparam_value};
257  }
258  }
259 
260  bool cur_load_successful = true;
261  bool check_size_exact = true;
262  if (cols <= 0) // this means that the cols dimension is dynamic or a zero matrix is expected
263  check_size_exact = false;
264 
265  std::vector<T> tmp_vec;
266  // try to load the parameter
267  const bool success = m_pp.getParam(name_prefixed, tmp_vec);
268  // check if the loaded vector has correct length
269  bool correct_size = (int)tmp_vec.size() == rows * cols;
270  if (!check_size_exact && !expect_zero_matrix)
271  correct_size = (int)tmp_vec.size() % rows == 0; // if the cols dimension is dynamic, the size just has to be divisable by rows
272 
273  if (success && correct_size)
274  {
275  // if successfully loaded, everything is in order
276  // transform the vector to the matrix
277  if (cols <= 0 && rows > 0)
278  cols = tmp_vec.size() / rows;
279  if (swap)
280  std::swap(rows, cols);
281  loaded = Eigen::Map<Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>, Eigen::Unaligned>(tmp_vec.data(), rows, cols);
282  used_rosparam_value = true;
283  } else
284  {
285  if (success && !correct_size)
286  {
287  // warn the user that this parameter was not successfully loaded because of wrong vector length (might be an oversight)
288  std::string warning =
289  std::string("Matrix parameter ") + name_prefixed
290  + std::string(" could not be loaded because the vector has a wrong length " + std::to_string(tmp_vec.size()) + " instead of expected ");
291  // process the message correctly based on whether the loaded matrix should be dynamic or static
292  if (cols <= 0) // for dynamic matrices
293  warning = warning + std::string("number divisible by ") + std::to_string(rows);
294  else // for static matrices
295  warning = warning + std::to_string(rows * cols);
296  print_warning(warning);
297  }
298  // if it was not loaded, the default value is used (set at the beginning of the function)
299  if (!optional)
300  {
301  // if the parameter was compulsory, alert the user and set the flag
302  printError(std::string("Could not load non-optional parameter ") + resolved(name_prefixed));
303  cur_load_successful = false;
304  }
305  }
306 
307  // check if load was a success
308  if (cur_load_successful)
309  {
310  if (m_print_values && printValues)
311  printValue(name_prefixed, loaded);
312  m_loaded_params.insert(name_prefixed);
313  } else
314  {
315  m_load_successful = false;
316  }
317  // finally, return the resulting value
318  return {loaded, used_rosparam_value};
319  }
320  //}
321 
322  /* loadMatrixStatic_internal helper function for loading static Eigen matrices //{ */
323  template <int rows, int cols, typename T>
324  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)
325  {
326  const auto [dynamic, loaded_ok] = loadMatrixX(name, MatrixX<T>(default_value), rows, cols, optional, unique, NO_SWAP);
327  return {dynamic, loaded_ok};
328  }
329  //}
330 
331  /* loadMatrixKnown_internal helper function for loading EigenXd matrices with known dimensions //{ */
332  template <typename T>
333  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)
334  {
335  MatrixX<T> loaded = default_value;
336  // first, check that at least one dimension is set
337  if (rows <= 0 || cols <= 0)
338  {
339  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name) + std::string(" (use loadMatrixDynamic?)"));
340  m_load_successful = false;
341  return {loaded, false};
342  }
343 
344  return loadMatrixX(name, default_value, rows, cols, optional, unique, NO_SWAP);
345  }
346  //}
347 
348  /* loadMatrixDynamic_internal helper function for loading Eigen matrices with one dynamic (unspecified) dimension //{ */
349  template <typename T>
350  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)
351  {
352  MatrixX<T> loaded = default_value;
353 
354  // next, check that at least one dimension is set
355  if (rows <= 0 && cols <= 0)
356  {
357  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name) + std::string(" (at least one dimension must be specified)"));
358  m_load_successful = false;
359  return {loaded, false};
360  }
361 
362  swap_t swap = NO_SWAP;
363  if (rows <= 0)
364  {
365  std::swap(rows, cols);
366  swap = SWAP;
367  }
368  return loadMatrixX(name, default_value, rows, cols, optional, unique, swap);
369  }
370  //}
371  //}
372 
373  /* loadMatrixArray_internal helper function for loading an array of EigenXd matrices with known dimensions //{ */
374  template <typename T>
375  std::vector<MatrixX<T>> loadMatrixArray_internal(const std::string& name, const std::vector<MatrixX<T>>& default_value, optional_t optional, unique_t unique)
376  {
377  const std::string name_prefixed = m_prefix + name;
378  int rows;
379  std::vector<int> cols;
380  bool success = true;
381  success = success && m_pp.getParam(name_prefixed + "/rows", rows);
382  success = success && m_pp.getParam(name_prefixed + "/cols", cols);
383 
384  std::vector<MatrixX<T>> loaded;
385  loaded.reserve(cols.size());
386 
387  int total_cols = 0;
388  /* check correctness of loaded parameters so far calculate the total dimension //{ */
389 
390  if (!success)
391  {
392  printError(std::string("Failed to load ") + resolved(name_prefixed) + std::string("/rows or ") + resolved(name_prefixed) + std::string("/cols"));
393  m_load_successful = false;
394  return default_value;
395  }
396  if (rows < 0)
397  {
398  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name_prefixed) + std::string(" (rows and cols must be >= 0)"));
399  m_load_successful = false;
400  return default_value;
401  }
402  for (const auto& col : cols)
403  {
404  if (col < 0)
405  {
406  printError(std::string("Invalid expected matrix dimensions for parameter ") + resolved(name_prefixed) + std::string(" (rows and cols must be >= 0)"));
407  m_load_successful = false;
408  return default_value;
409  }
410  total_cols += col;
411  }
412 
413  //}
414 
415  const auto [loaded_matrix, loaded_ok] = loadMatrixX(name + "/data", MatrixX<T>(), rows, total_cols, optional, unique, NO_SWAP, false);
416  /* std::cout << "loaded_matrix: " << loaded_matrix << std::endl; */
417  /* std::cout << "loaded_matrix: " << loaded_matrix.rows() << "x" << loaded_matrix.cols() << std::endl; */
418  /* std::cout << "expected dims: " << rows << "x" << total_cols << std::endl; */
419  if (loaded_matrix.rows() != rows || loaded_matrix.cols() != total_cols)
420  {
421  m_load_successful = false;
422  return default_value;
423  }
424 
425  int cols_loaded = 0;
426  for (unsigned it = 0; it < cols.size(); it++)
427  {
428  const int cur_cols = cols.at(it);
429  const MatrixX<T> cur_mat = loaded_matrix.block(0, cols_loaded, rows, cur_cols);
430  /* std::cout << "cur_mat: " << cur_mat << std::endl; */
431  loaded.push_back(cur_mat);
432  cols_loaded += cur_cols;
433  printValue(name_prefixed + "/matrix#" + std::to_string(it), cur_mat);
434  }
435  return loaded;
436  }
437  //}
438 
439  /* load helper function for generic types //{ */
440  // This function tries to load a parameter with name 'name' and a default value.
441  // You can use the flag 'optional' to not throw a ROS_ERROR when the parameter
442  // cannot be loaded and the flag 'printValues' to set whether the loaded
443  // value and name of the parameter should be printed to cout.
444  // If 'optional' is set to false and the parameter could not be loaded,
445  // the flag 'load_successful' is set to false and a ROS_ERROR message
446  // is printer.
447  // If 'unique' flag is set to false then the parameter is not checked
448  // for being loaded twice.
449  // Returns a tuple, containing either the loaded or the default value and a bool,
450  // indicating if the value was loaded (true) or the default value was used (false).
451  template <typename T>
452  std::pair<T, bool> load(const std::string& name, const T& default_value, optional_t optional = OPTIONAL, unique_t unique = UNIQUE)
453  {
454  const std::string name_prefixed = m_prefix + name;
455  T loaded = default_value;
456  if (unique && check_duplicit_loading(name_prefixed))
457  return {loaded, false};
458 
459  bool cur_load_successful = true;
460  // try to load the parameter
461  const bool success = m_pp.getParam(name_prefixed, loaded);
462  if (!success)
463  {
464  // if it was not loaded, set the default value
465  loaded = default_value;
466  if (!optional)
467  {
468  // if the parameter was compulsory, alert the user and set the flag
469  printError(std::string("Could not load non-optional parameter ") + resolved(name_prefixed));
470  cur_load_successful = false;
471  }
472  }
473 
474  if (cur_load_successful)
475  {
476  // everything is fine and just print the name_prefixed and value if required
477  if (m_print_values)
478  printValue(name_prefixed, loaded);
479  // mark the param name_prefixed as successfully loaded
480  m_loaded_params.insert(name_prefixed);
481  } else
482  {
483  m_load_successful = false;
484  }
485  // finally, return the resulting value
486  return {loaded, success};
487  }
488  //}
489 
490 public:
498  ParamLoader(const ros::NodeHandle& nh, bool printValues = true, std::string_view node_name = std::string())
499  : m_load_successful(true),
500  m_print_values(printValues),
501  m_node_name(node_name),
502  m_nh(nh),
503  m_pp(nh, m_node_name)
504  {
505  /* std::cout << "Initialized1 ParamLoader for node " << node_name << std::endl; */
506  }
507 
508  /* Constructor overloads //{ */
515  ParamLoader(const ros::NodeHandle& nh, std::string_view node_name)
516  : ParamLoader(nh, true, node_name)
517  {
518  /* std::cout << "Initialized2 ParamLoader for node " << node_name << std::endl; */
519  }
520 
527  ParamLoader(const std::string& filepath, const ros::NodeHandle& nh)
528  : ParamLoader(nh, "none")
529  {
530  YAML::Node node = YAML::Load(filepath);
531  }
532  //}
533 
534  /* setPrefix function //{ */
535 
541  void setPrefix(const std::string& prefix)
542  {
543  m_prefix = prefix;
544  }
545 
546  //}
547 
548  /* getPrefix function //{ */
549 
555  std::string getPrefix()
556  {
557  return m_prefix;
558  }
559 
560  //}
561 
562  /* addYamlFile() function //{ */
563 
570  bool addYamlFile(const std::string& filepath)
571  {
572  return m_pp.addYamlFile(filepath);
573  }
574  //}
575 
576  /* addYamlFileFromParam() function //{ */
577 
584  bool addYamlFileFromParam(const std::string& param_name)
585  {
586  std::string filepath;
587  if (!loadParam(param_name, filepath))
588  return false;
589  return m_pp.addYamlFile(filepath);
590  }
591  //}
592 
593  /* loadedSuccessfully function //{ */
600  {
601  return m_load_successful;
602  }
603  //}
604 
605  /* resetLoadedSuccessfully function //{ */
610  {
611  m_load_successful = true;
612  }
613  //}
614 
615  /* resetUniques function //{ */
620  {
621  m_loaded_params.clear();
622  }
623  //}
624 
625  /* loadParam function for optional parameters //{ */
638  template <typename T>
639  bool loadParam(const std::string& name, T& out_value, const T& default_value)
640  {
641  const auto [ret, success] = load<T>(name, default_value, OPTIONAL, UNIQUE);
642  out_value = ret;
643  return success;
644  }
656  template <typename T>
657  T loadParam2(const std::string& name, const T& default_value)
658  {
659  const auto loaded = load<T>(name, default_value, OPTIONAL, UNIQUE);
660  return loaded.first;
661  }
674  template <typename T>
675  bool loadParamReusable(const std::string& name, T& out_value, const T& default_value)
676  {
677  const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
678  out_value = ret;
679  return success;
680  }
692  template <typename T>
693  T loadParamReusable2(const std::string& name, const T& default_value)
694  {
695  const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
696  return ret;
697  }
698  //}
699 
700  /* loadParam function for compulsory parameters //{ */
712  template <typename T>
713  bool loadParam(const std::string& name, T& out_value)
714  {
715  const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
716  out_value = ret;
717  return success;
718  }
729  template <typename T>
730  T loadParam2(const std::string& name)
731  {
732  const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
733  return ret;
734  }
746  template <typename T>
747  bool loadParamReusable(const std::string& name, T& out_value)
748  {
749  const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
750  out_value = ret;
751  return success;
752  }
763  template <typename T>
764  T loadParamReusable2(const std::string& name)
765  {
766  const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
767  return ret;
768  }
769  //}
770 
771  /* loadParam specializations for ros::Duration type //{ */
772 
783  bool loadParam(const std::string& name, ros::Duration& out, const ros::Duration& default_value)
784  {
785  double secs;
786  const bool ret = loadParam<double>(name, secs, default_value.toSec());
787  out = ros::Duration(secs);
788  return ret;
789  }
790 
800  bool loadParam(const std::string& name, ros::Duration& out)
801  {
802  double secs;
803  const bool ret = loadParam<double>(name, secs);
804  out = ros::Duration(secs);
805  return ret;
806  }
807 
808  //}
809 
810  /* loadParam specializations for std_msgs::ColorRGBA type //{ */
811 
822  bool loadParam(const std::string& name, std_msgs::ColorRGBA& out, const std_msgs::ColorRGBA& default_value = {})
823  {
824  std_msgs::ColorRGBA res;
825  bool ret = true;
826  ret = ret & loadParam(name+"/r", res.r, default_value.r);
827  ret = ret & loadParam(name+"/g", res.g, default_value.g);
828  ret = ret & loadParam(name+"/b", res.b, default_value.b);
829  ret = ret & loadParam(name+"/a", res.a, default_value.a);
830  if (ret)
831  out = res;
832  return ret;
833  }
834 
844  std_msgs::ColorRGBA loadParam2(const std::string& name, const std_msgs::ColorRGBA& default_value = {})
845  {
846  std_msgs::ColorRGBA ret;
847  loadParam(name, ret, default_value);
848  return ret;
849  }
850 
851  //}
852 
853  /* loadParam specializations for XmlRpc::Value type //{ */
854 
867  bool loadParam(const std::string& name, XmlRpc::XmlRpcValue& out, const XmlRpc::XmlRpcValue& default_value)
868  {
869  return loadParam<XmlRpc::XmlRpcValue>(name, out, default_value);
870  }
871 
883  bool loadParam(const std::string& name, XmlRpc::XmlRpcValue& out)
884  {
885  return loadParam<XmlRpc::XmlRpcValue>(name, out);
886  }
887 
899  XmlRpc::XmlRpcValue loadParam2(const std::string& name, const XmlRpc::XmlRpcValue& default_value)
900  {
901  return loadParam2<XmlRpc::XmlRpcValue>(name, default_value);
902  }
903 
904  //}
905 
906  /* loadParam specializations and convenience functions for Eigen dynamic matrix type //{ */
907 
922  template <typename T>
923  bool loadParam(const std::string& name, MatrixX<T>& mat, const MatrixX<T>& default_value)
924  {
925  const int rows = default_value.rows();
926  const int cols = default_value.cols();
927  const bool loaded_ok = loadMatrixDynamic(name, mat, default_value, rows, cols);
928  return loaded_ok;
929  }
930 
944  template <typename T>
945  MatrixX<T> loadParam2(const std::string& name, const MatrixX<T>& default_value)
946  {
947  MatrixX<T> ret;
948  loadParam(name, ret, default_value);
949  return ret;
950  }
951 
952  //}
953 
954  // loadMatrixStatic function for loading of static Eigen::Matrices //{
955 
973  template <int rows, int cols, typename T>
974  bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat)
975  {
976  const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>::Zero(), COMPULSORY, UNIQUE);
977  mat = ret;
978  return loaded_ok;
979  }
980 
999  template <int rows, int cols, typename T, typename Derived>
1000  bool loadMatrixStatic(const std::string& name, Eigen::Matrix<T, rows, cols>& mat, const Eigen::MatrixBase<Derived>& default_value)
1001  {
1002  const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>(default_value), OPTIONAL, UNIQUE);
1003  mat = ret;
1004  return loaded_ok;
1005  }
1006 
1023  template <int rows, int cols, typename T = double>
1024  Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name)
1025  {
1026  Eigen::Matrix<T, rows, cols> ret;
1027  loadMatrixStatic(name, ret);
1028  return ret;
1029  }
1030 
1048  template <int rows, int cols, typename T, typename Derived>
1049  Eigen::Matrix<T, rows, cols> loadMatrixStatic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value)
1050  {
1051  Eigen::Matrix<T, rows, cols> ret;
1052  loadMatrixStatic(name, ret, default_value);
1053  return ret;
1054  }
1055  //}
1056 
1057  // loadMatrixKnown function for loading of Eigen matrices with known dimensions //{
1058 
1074  template <typename T>
1075  bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, int rows, int cols)
1076  {
1077  const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
1078  mat = ret;
1079  return loaded_ok;
1080  }
1081 
1098  template <typename T, typename Derived>
1099  bool loadMatrixKnown(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
1100  {
1101  const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
1102  mat = ret;
1103  return loaded_ok;
1104  }
1105 
1120  template <typename T = double>
1121  MatrixX<T> loadMatrixKnown2(const std::string& name, int rows, int cols)
1122  {
1123  MatrixX<T> ret;
1124  loadMatrixKnown(name, ret, rows, cols);
1125  return ret;
1126  }
1127 
1143  template <typename T, typename Derived>
1144  MatrixX<T> loadMatrixKnown2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
1145  {
1146  MatrixX<T> ret;
1147  loadMatrixKnown(name, ret, default_value, rows, cols);
1148  return ret;
1149  }
1150  //}
1151 
1152  // loadMatrixDynamic function for half-dynamic loading of MatrixX<T> //{
1153 
1169  template <typename T>
1170  bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, int rows, int cols)
1171  {
1172  const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
1173  mat = ret;
1174  return loaded_ok;
1175  }
1176 
1193  template <typename T, typename Derived>
1194  bool loadMatrixDynamic(const std::string& name, MatrixX<T>& mat, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
1195  {
1196  const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
1197  mat = ret;
1198  return loaded_ok;
1199  }
1200 
1215  template <typename T = double>
1216  MatrixX<T> loadMatrixDynamic2(const std::string& name, int rows, int cols)
1217  {
1218  MatrixX<T> ret;
1219  loadMatrixDynamic(name, ret, rows, cols);
1220  return ret;
1221  }
1222 
1238  template <typename T, typename Derived>
1239  MatrixX<T> loadMatrixDynamic2(const std::string& name, const Eigen::MatrixBase<Derived>& default_value, int rows, int cols)
1240  {
1241  MatrixX<T> ret;
1242  loadMatrixDynamic(name, ret, default_value, rows, cols);
1243  return ret;
1244  }
1245 
1246  //}
1247 
1248  // loadMatrixArray function for loading of an array of MatrixX<T> with known dimensions //{
1281  template <typename T>
1282  void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat)
1283  {
1284  mat = loadMatrixArray2<double>(name);
1285  }
1286 
1298  template <typename T>
1299  void loadMatrixArray(const std::string& name, std::vector<MatrixX<T>>& mat, const std::vector<MatrixX<T>>& default_value)
1300  {
1301  mat = loadMatrixArray2(name, default_value);
1302  }
1303 
1314  template <typename T = double>
1315  std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name)
1316  {
1317  return loadMatrixArray_internal(name, std::vector<MatrixX<T>>(), COMPULSORY, UNIQUE);
1318  }
1319 
1331  template <typename T>
1332  std::vector<MatrixX<T>> loadMatrixArray2(const std::string& name, const std::vector<MatrixX<T>>& default_value)
1333  {
1334  return loadMatrixArray_internal(name, default_value, OPTIONAL, UNIQUE);
1335  }
1336  //}
1337 
1338  //}
1339 
1340 };
1341 //}
1342 
1352  template <>
1353  ros::Duration ParamLoader::loadParam2<ros::Duration>(const std::string& name, const ros::Duration& default_value);
1354 
1363  template <>
1364  ros::Duration ParamLoader::loadParam2<ros::Duration>(const std::string& name);
1365 
1366 } // namespace mrs_lib
1367 
1368 #endif // PARAM_LOADER_H
mrs_lib::ParamLoader::resetLoadedSuccessfully
void resetLoadedSuccessfully()
Resets the loadedSuccessfully flag back to true.
Definition: param_loader.h:609
mrs_lib::ParamProvider::addYamlFile
bool addYamlFile(const std::string &filepath)
Add a YAML file to be parsed and used for loading parameters.
Definition: param_provider.cpp:18
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, XmlRpc::XmlRpcValue &out, const XmlRpc::XmlRpcValue &default_value)
An overload for loading an optional XmlRpc::XmlRpcValue.
Definition: param_loader.h:867
mrs_lib::ParamLoader::addYamlFile
bool addYamlFile(const std::string &filepath)
Adds the specified file as a source of static parameters.
Definition: param_loader.h:570
mrs_lib::ParamLoader::loadMatrixDynamic
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.h:1170
mrs_lib::ParamLoader::loadMatrixKnown2
MatrixX< T > loadMatrixKnown2(const std::string &name, const Eigen::MatrixBase< Derived > &default_value, int rows, int cols)
Specialized method for loading Eigen matrix parameters with default value.
Definition: param_loader.h:1144
mrs_lib::ParamLoader::setPrefix
void setPrefix(const std::string &prefix)
All loaded parameters will be prefixed with this string.
Definition: param_loader.h:541
mrs_lib::ParamLoader::loadMatrixArray
void loadMatrixArray(const std::string &name, std::vector< MatrixX< T >> &mat, const std::vector< MatrixX< T >> &default_value)
Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matric...
Definition: param_loader.h:1299
mrs_lib::ParamLoader::loadMatrixDynamic
bool loadMatrixDynamic(const std::string &name, MatrixX< T > &mat, const Eigen::MatrixBase< Derived > &default_value, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition: param_loader.h:1194
mrs_lib::ParamLoader::loadMatrixStatic
bool loadMatrixStatic(const std::string &name, Eigen::Matrix< T, rows, cols > &mat, const Eigen::MatrixBase< Derived > &default_value)
Specialized method for loading Eigen matrix parameters with default value.
Definition: param_loader.h:1000
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, ros::Duration &out)
An overload for loading ros::Duration.
Definition: param_loader.h:800
mrs_lib::ParamLoader::loadParamReusable
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.h:675
mrs_lib::ParamLoader::loadMatrixStatic2
Eigen::Matrix< T, rows, cols > loadMatrixStatic2(const std::string &name)
Specialized method for loading compulsory Eigen matrix parameters.
Definition: param_loader.h:1024
mrs_lib::ParamProvider::getParam
bool getParam(const std::string &param_name, T &value_out) const
Gets the value of a parameter.
Definition: param_provider.hpp:9
mrs_lib::ParamLoader::loadParam2
T loadParam2(const std::string &name, const T &default_value)
Loads a parameter from the rosparam server with a default value.
Definition: param_loader.h:657
mrs_lib::ParamLoader::loadParam2
T loadParam2(const std::string &name)
Loads a compulsory parameter from the rosparam server.
Definition: param_loader.h:730
mrs_lib::ParamLoader::loadParamReusable2
T loadParamReusable2(const std::string &name)
Loads a compulsory parameter from the rosparam server.
Definition: param_loader.h:764
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, std_msgs::ColorRGBA &out, const std_msgs::ColorRGBA &default_value={})
An overload for loading std_msgs::ColorRGBA.
Definition: param_loader.h:822
mrs_lib::ParamLoader::loadMatrixKnown
bool loadMatrixKnown(const std::string &name, MatrixX< T > &mat, const Eigen::MatrixBase< Derived > &default_value, int rows, int cols)
Specialized method for loading Eigen matrix parameters with default value.
Definition: param_loader.h:1099
mrs_lib::ParamLoader::loadMatrixKnown
bool loadMatrixKnown(const std::string &name, MatrixX< T > &mat, int rows, int cols)
Specialized method for loading compulsory Eigen matrix parameters.
Definition: param_loader.h:1075
mrs_lib::ParamLoader::loadMatrixStatic
bool loadMatrixStatic(const std::string &name, Eigen::Matrix< T, rows, cols > &mat)
Specialized method for loading compulsory Eigen matrix parameters.
Definition: param_loader.h:974
mrs_lib::ParamLoader::ParamLoader
ParamLoader(const ros::NodeHandle &nh, std::string_view node_name)
Convenience overload to enable writing ParamLoader pl(nh, node_name);.
Definition: param_loader.h:515
mrs_lib::ParamLoader::loadParamReusable2
T loadParamReusable2(const std::string &name, const T &default_value)
Loads an optional reusable parameter from the rosparam server.
Definition: param_loader.h:693
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, ros::Duration &out, const ros::Duration &default_value)
An overload for loading ros::Duration.
Definition: param_loader.h:783
mrs_lib::ParamLoader::loadMatrixArray2
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.h:1315
mrs_lib::ParamLoader::loadedSuccessfully
bool loadedSuccessfully()
Indicates whether all compulsory parameters were successfully loaded.
Definition: param_loader.h:599
mrs_lib::ParamLoader::ParamLoader
ParamLoader(const std::string &filepath, const ros::NodeHandle &nh)
Convenience overload to enable writing ParamLoader pl(nh, "node_name");.
Definition: param_loader.h:527
mrs_lib::ParamLoader::loadMatrixArray
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.h:1282
mrs_lib::ParamLoader::loadParam2
XmlRpc::XmlRpcValue loadParam2(const std::string &name, const XmlRpc::XmlRpcValue &default_value)
An overload for loading an optional XmlRpc::XmlRpcValue.
Definition: param_loader.h:899
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::ParamLoader::resetUniques
void resetUniques()
Resets the list of already loaded parameter names used when checking for uniqueness.
Definition: param_loader.h:619
mrs_lib::ParamLoader::loadParam
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.h:639
mrs_lib::ParamLoader::loadMatrixArray2
std::vector< MatrixX< T > > loadMatrixArray2(const std::string &name, const std::vector< MatrixX< T >> &default_value)
Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matric...
Definition: param_loader.h:1332
mrs_lib::ParamLoader::loadParamReusable
bool loadParamReusable(const std::string &name, T &out_value)
Loads a compulsory parameter from the rosparam server.
Definition: param_loader.h:747
mrs_lib::ParamLoader
Convenience class for loading parameters from rosparam server.
Definition: param_loader.h:43
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, MatrixX< T > &mat, const MatrixX< T > &default_value)
An overload for loading Eigen matrices.
Definition: param_loader.h:923
mrs_lib::ParamLoader::loadParam2
MatrixX< T > loadParam2(const std::string &name, const MatrixX< T > &default_value)
An overload for loading Eigen matrices.
Definition: param_loader.h:945
mrs_lib::ParamLoader::loadParam2
std_msgs::ColorRGBA loadParam2(const std::string &name, const std_msgs::ColorRGBA &default_value={})
An overload for loading std_msgs::ColorRGBA.
Definition: param_loader.h:844
mrs_lib::ParamLoader::getPrefix
std::string getPrefix()
Returns the current parameter name prefix.
Definition: param_loader.h:555
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, T &out_value)
Loads a compulsory parameter from the rosparam server.
Definition: param_loader.h:713
mrs_lib::ParamLoader::loadMatrixKnown2
MatrixX< T > loadMatrixKnown2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory Eigen matrix parameters.
Definition: param_loader.h:1121
mrs_lib::ParamLoader::loadMatrixStatic2
Eigen::Matrix< T, rows, cols > loadMatrixStatic2(const std::string &name, const Eigen::MatrixBase< Derived > &default_value)
Specialized method for loading Eigen matrix parameters with default value.
Definition: param_loader.h:1049
mrs_lib::ParamLoader::addYamlFileFromParam
bool addYamlFileFromParam(const std::string &param_name)
Loads a filepath from a parameter loads that file as a YAML.
Definition: param_loader.h:584
mrs_lib::ParamLoader::loadMatrixDynamic2
MatrixX< T > loadMatrixDynamic2(const std::string &name, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition: param_loader.h:1216
mrs_lib::ParamLoader::loadParam
bool loadParam(const std::string &name, XmlRpc::XmlRpcValue &out)
An overload for loading a compulsory XmlRpc::XmlRpcValue.
Definition: param_loader.h:883
mrs_lib::ParamProvider
Helper class for ParamLoader.
Definition: param_provider.h:28
param_provider.h
Defines ParamProvider - a helper class for ParamLoader.
mrs_lib::ParamLoader::ParamLoader
ParamLoader(const ros::NodeHandle &nh, bool printValues=true, std::string_view node_name=std::string())
Main constructor.
Definition: param_loader.h:498
mrs_lib::ParamLoader::loadMatrixDynamic2
MatrixX< T > loadMatrixDynamic2(const std::string &name, const Eigen::MatrixBase< Derived > &default_value, int rows, int cols)
Specialized method for loading compulsory dynamic Eigen matrix parameters.
Definition: param_loader.h:1239