4#include <mrs_lib/param_loader.h>
12 void ParamLoader::printValue(
const resolved_name_t& name,
const T& value)
const
14 if (m_node_name.empty())
15 std::cout <<
"\t" << name <<
":\t" << value << std::endl;
17 RCLCPP_INFO_STREAM(m_node->get_logger(),
"[" << m_node_name <<
"]: parameter '" << name <<
"':\t" << value);
21 std::ostream&
operator<<(std::ostream& os,
const Eigen::MatrixX<T>& var)
25 const Eigen::IOFormat fmt;
26 return os << var.format(fmt);
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)
38 MatrixX<T> loaded = default_value;
39 bool used_rosparam_value =
false;
41 if (unique && check_duplicit_loading(resolved_name))
42 return {loaded, used_rosparam_value};
47 printError(std::string(
"Invalid expected matrix dimensions for parameter ") + resolved_name.str);
48 m_load_successful =
false;
49 return {loaded, used_rosparam_value};
51 const bool expect_zero_matrix = rows == 0;
52 if (expect_zero_matrix) {
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};
61 bool cur_load_successful =
true;
62 bool check_size_exact =
true;
64 check_size_exact =
false;
66 std::vector<T> tmp_vec;
68 const bool success = m_pp.
getParam(resolved_name, tmp_vec);
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;
74 if (success && correct_size) {
77 if (cols <= 0 && rows > 0)
78 cols = tmp_vec.size() / rows;
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;
84 if (success && !correct_size) {
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 ");
91 warning = warning + std::string(
"number divisible by ") + std::to_string(rows);
93 warning = warning + std::to_string(rows * cols);
94 printWarning(warning);
99 printError(std::string(
"Could not load non-optional parameter ") + resolved_name.str);
100 cur_load_successful =
false;
105 if (cur_load_successful) {
106 if (m_print_values && printValues)
107 printValue(resolved_name, loaded);
108 m_loaded_params.insert(resolved_name);
110 m_load_successful =
false;
113 return {loaded, used_rosparam_value};
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)
121 const auto [dynamic, loaded_ok] = loadMatrixX(name, MatrixX<T>(default_value), rows, cols, optional, unique, NO_SWAP);
122 return {dynamic, loaded_ok};
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)
130 MatrixX<T> loaded = default_value;
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};
138 return loadMatrixX(name, default_value, rows, cols, optional, unique, NO_SWAP);
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)
146 MatrixX<T> loaded = default_value;
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};
156 swap_t swap = NO_SWAP;
158 std::swap(rows, cols);
161 return loadMatrixX(name, default_value, rows, cols, optional, unique, swap);
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)
171 std::vector<long int> cols;
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);
176 std::vector<MatrixX<T>> loaded;
177 loaded.reserve(cols.size());
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;
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;
192 for (
const auto& col : cols) {
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;
203 const auto [loaded_matrix, loaded_ok] = loadMatrixX(name +
"/data", MatrixX<T>(), rows, total_cols, optional, unique, NO_SWAP,
false);
207 if (loaded_matrix.rows() != rows || loaded_matrix.cols() != total_cols) {
208 m_load_successful =
false;
209 return default_value;
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);
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);
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)
243 T loaded = default_value;
244 if (unique && check_duplicit_loading(resolved_name))
245 return {loaded,
false};
247 bool cur_load_successful =
true;
249 const bool success = m_pp.
getParam(resolved_name, loaded);
252 loaded = default_value;
255 printError(std::string(
"Could not load non-optional parameter ") + resolved_name.str);
256 cur_load_successful =
false;
260 if (cur_load_successful) {
263 printValue(resolved_name, loaded);
265 m_loaded_params.insert(resolved_name);
267 m_load_successful =
false;
270 return {loaded, success};
276 template <
typename T>
279 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, UNIQUE);
294 template <
typename T>
297 const auto loaded = load<T>(name, default_value, OPTIONAL, UNIQUE);
312 template <
typename T>
315 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
330 template <
typename T>
333 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
350 template <
typename T>
353 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
367 template <
typename T>
370 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
384 template <
typename T>
387 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
401 template <
typename T>
404 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
425 template <
typename T>
428 const int rows = default_value.rows();
429 const int cols = default_value.cols();
447 template <
typename T>
476 template <
int rows,
int cols,
typename T>
479 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>::Zero(), COMPULSORY, UNIQUE);
501 template <
int rows,
int cols,
typename T,
typename Derived>
504 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>(default_value), OPTIONAL, UNIQUE);
525 template <
int rows,
int cols,
typename T>
528 Eigen::Matrix<T, rows, cols> ret;
549 template <
int rows,
int cols,
typename T,
typename Derived>
552 Eigen::Matrix<T, rows, cols> ret;
575 template <
typename T>
578 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
598 template <
typename T,
typename Derived>
601 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
620 template <
typename T>
642 template <
typename T,
typename Derived>
668 template <
typename T>
671 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
692 template <
typename T,
typename Derived>
695 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
714 template <
typename T>
736 template <
typename T,
typename Derived>
779 template <
typename T>
782 mat = loadMatrixArray2<double>(name);
796 template <
typename T>
812 template <
typename T>
815 return loadMatrixArray_internal(name, std::vector<MatrixX<T>>(), COMPULSORY, UNIQUE);
829 template <
typename T>
832 return loadMatrixArray_internal(name, default_value, OPTIONAL, UNIQUE);
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 ¶m_name) const
Returns the parameter name with prefixes and subnode namespaces.
Definition param_provider.cpp:148
bool getParam(const std::string ¶m_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