13 #include <unordered_set>
15 #include <Eigen/Dense>
16 #include <std_msgs/ColorRGBA.h>
64 using MatrixX = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
67 bool m_load_successful, m_print_values;
68 std::string m_node_name;
70 const ros::NodeHandle& m_nh;
72 std::unordered_set<std::string> m_loaded_params;
76 void printError(
const std::string& str)
78 if (m_node_name.empty())
79 ROS_ERROR_STREAM(str);
81 ROS_ERROR_STREAM(
"[" << m_node_name <<
"]: " << str);
83 void print_warning(
const std::string& str)
85 if (m_node_name.empty())
88 ROS_WARN_STREAM(
"[" << m_node_name <<
"]: " << str);
95 void printValue(
const std::string& name,
const T& value)
97 if (m_node_name.empty())
98 std::cout <<
"\t" << name <<
":\t" << value << std::endl;
100 ROS_INFO_STREAM(
"[" << m_node_name <<
"]: parameter '" << name <<
"':\t" << value);
103 template <
typename T>
104 void printValue(
const std::string& name,
const std::vector<T>& value)
106 std::stringstream strstr;
107 if (m_node_name.empty())
109 strstr << name <<
":\t";
111 for (
const auto& elem : value)
114 if (it < value.size() - 1)
118 if (m_node_name.empty())
119 std::cout << strstr.str() << std::endl;
121 ROS_INFO_STREAM(
"[" << m_node_name <<
"]: parameter '" << strstr.str());
124 template <
typename T1,
typename T2>
125 void printValue(
const std::string& name,
const std::map<T1, T2>& value)
127 std::stringstream strstr;
128 if (m_node_name.empty())
130 strstr << name <<
":" << std::endl;
132 for (
const auto& pair : value)
134 strstr << pair.first <<
" = " << pair.second;
135 if (it < value.size() - 1)
139 if (m_node_name.empty())
140 std::cout << strstr.str() << std::endl;
142 ROS_INFO_STREAM(
"[" << m_node_name <<
"]: parameter '" << strstr.str());
145 template <
typename T>
146 void printValue(
const std::string& name,
const MatrixX<T>& value)
148 std::stringstream strstr;
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;
156 ROS_INFO_STREAM(
"[" << m_node_name <<
"]: parameter '" << name <<
"':" << std::endl << strstr.str());
159 std::string printValue_recursive(
const std::string& name, XmlRpc::XmlRpcValue& value,
unsigned depth = 0)
161 std::stringstream strstr;
162 for (
unsigned it = 0; it < depth; it++)
164 strstr << name <<
":";
165 switch (value.getType())
167 case XmlRpc::XmlRpcValue::TypeArray:
169 for (
int it = 0; it < value.size(); it++)
172 const std::string name =
"[" + std::to_string(it) +
"]";
173 strstr << printValue_recursive(name, value[it], depth+1);
177 case XmlRpc::XmlRpcValue::TypeStruct:
180 for (
auto& pair : value)
183 strstr << printValue_recursive(pair.first, pair.second, depth+1);
190 strstr <<
"\t" << value;
197 void printValue(
const std::string& name, XmlRpc::XmlRpcValue& value)
199 const std::string txt = printValue_recursive(name, value);
200 if (m_node_name.empty())
201 std::cout << txt << std::endl;
203 ROS_INFO_STREAM(
"[" << m_node_name <<
"]: parameter '" << txt);
208 std::string resolved(
const std::string& param_name)
210 return m_nh.resolveName(param_name);
215 bool check_duplicit_loading(
const std::string& name)
217 if (m_loaded_params.count(name))
219 printError(std::string(
"Tried to load parameter ") + name + std::string(
" twice"));
220 m_load_successful =
false;
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)
234 const std::string name_prefixed = m_prefix + name;
235 MatrixX<T> loaded = default_value;
236 bool used_rosparam_value =
false;
238 if (unique && check_duplicit_loading(name_prefixed))
239 return {loaded, used_rosparam_value};
245 printError(std::string(
"Invalid expected matrix dimensions for parameter ") + resolved(name_prefixed));
246 m_load_successful =
false;
247 return {loaded, used_rosparam_value};
249 const bool expect_zero_matrix = rows == 0;
250 if (expect_zero_matrix)
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};
260 bool cur_load_successful =
true;
261 bool check_size_exact =
true;
263 check_size_exact =
false;
265 std::vector<T> tmp_vec;
267 const bool success = m_pp.
getParam(name_prefixed, tmp_vec);
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;
273 if (success && correct_size)
277 if (cols <= 0 && rows > 0)
278 cols = tmp_vec.size() / rows;
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;
285 if (success && !correct_size)
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 ");
293 warning = warning + std::string(
"number divisible by ") + std::to_string(rows);
295 warning = warning + std::to_string(rows * cols);
296 print_warning(warning);
302 printError(std::string(
"Could not load non-optional parameter ") + resolved(name_prefixed));
303 cur_load_successful =
false;
308 if (cur_load_successful)
310 if (m_print_values && printValues)
311 printValue(name_prefixed, loaded);
312 m_loaded_params.insert(name_prefixed);
315 m_load_successful =
false;
318 return {loaded, used_rosparam_value};
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)
326 const auto [dynamic, loaded_ok] = loadMatrixX(name, MatrixX<T>(default_value), rows, cols, optional, unique, NO_SWAP);
327 return {dynamic, loaded_ok};
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)
335 MatrixX<T> loaded = default_value;
337 if (rows <= 0 || cols <= 0)
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};
344 return loadMatrixX(name, default_value, rows, cols, optional, unique, NO_SWAP);
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)
352 MatrixX<T> loaded = default_value;
355 if (rows <= 0 && cols <= 0)
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};
362 swap_t swap = NO_SWAP;
365 std::swap(rows, cols);
368 return loadMatrixX(name, default_value, rows, cols, optional, unique, swap);
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)
377 const std::string name_prefixed = m_prefix + name;
379 std::vector<int> cols;
381 success = success && m_pp.
getParam(name_prefixed +
"/rows", rows);
382 success = success && m_pp.
getParam(name_prefixed +
"/cols", cols);
384 std::vector<MatrixX<T>> loaded;
385 loaded.reserve(cols.size());
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;
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;
402 for (
const auto& col : cols)
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;
415 const auto [loaded_matrix, loaded_ok] = loadMatrixX(name +
"/data", MatrixX<T>(), rows, total_cols, optional, unique, NO_SWAP,
false);
419 if (loaded_matrix.rows() != rows || loaded_matrix.cols() != total_cols)
421 m_load_successful =
false;
422 return default_value;
426 for (
unsigned it = 0; it < cols.size(); it++)
428 const int cur_cols = cols.at(it);
429 const MatrixX<T> cur_mat = loaded_matrix.block(0, cols_loaded, rows, cur_cols);
431 loaded.push_back(cur_mat);
432 cols_loaded += cur_cols;
433 printValue(name_prefixed +
"/matrix#" + std::to_string(it), cur_mat);
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)
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};
459 bool cur_load_successful =
true;
461 const bool success = m_pp.
getParam(name_prefixed, loaded);
465 loaded = default_value;
469 printError(std::string(
"Could not load non-optional parameter ") + resolved(name_prefixed));
470 cur_load_successful =
false;
474 if (cur_load_successful)
478 printValue(name_prefixed, loaded);
480 m_loaded_params.insert(name_prefixed);
483 m_load_successful =
false;
486 return {loaded, success};
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),
503 m_pp(nh, m_node_name)
515 ParamLoader(
const ros::NodeHandle& nh, std::string_view node_name)
527 ParamLoader(
const std::string& filepath,
const ros::NodeHandle& nh)
530 YAML::Node node = YAML::Load(filepath);
586 std::string filepath;
601 return m_load_successful;
611 m_load_successful =
true;
621 m_loaded_params.clear();
638 template <
typename T>
639 bool loadParam(
const std::string& name, T& out_value,
const T& default_value)
641 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, UNIQUE);
656 template <
typename T>
657 T
loadParam2(
const std::string& name,
const T& default_value)
659 const auto loaded = load<T>(name, default_value, OPTIONAL, UNIQUE);
674 template <
typename T>
677 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
692 template <
typename T>
695 const auto [ret, success] = load<T>(name, default_value, OPTIONAL, REUSABLE);
712 template <
typename T>
715 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
729 template <
typename T>
732 const auto [ret, success] = load<T>(name, T(), COMPULSORY, UNIQUE);
746 template <
typename T>
749 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
763 template <
typename T>
766 const auto [ret, success] = load<T>(name, T(), COMPULSORY, REUSABLE);
783 bool loadParam(
const std::string& name, ros::Duration& out,
const ros::Duration& default_value)
786 const bool ret = loadParam<double>(name, secs, default_value.toSec());
787 out = ros::Duration(secs);
800 bool loadParam(
const std::string& name, ros::Duration& out)
803 const bool ret = loadParam<double>(name, secs);
804 out = ros::Duration(secs);
822 bool loadParam(
const std::string& name, std_msgs::ColorRGBA& out,
const std_msgs::ColorRGBA& default_value = {})
824 std_msgs::ColorRGBA res;
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);
844 std_msgs::ColorRGBA
loadParam2(
const std::string& name,
const std_msgs::ColorRGBA& default_value = {})
846 std_msgs::ColorRGBA ret;
867 bool loadParam(
const std::string& name, XmlRpc::XmlRpcValue& out,
const XmlRpc::XmlRpcValue& default_value)
869 return loadParam<XmlRpc::XmlRpcValue>(name, out, default_value);
883 bool loadParam(
const std::string& name, XmlRpc::XmlRpcValue& out)
885 return loadParam<XmlRpc::XmlRpcValue>(name, out);
899 XmlRpc::XmlRpcValue
loadParam2(
const std::string& name,
const XmlRpc::XmlRpcValue& default_value)
901 return loadParam2<XmlRpc::XmlRpcValue>(name, default_value);
922 template <
typename T>
923 bool loadParam(
const std::string& name, MatrixX<T>& mat,
const MatrixX<T>& default_value)
925 const int rows = default_value.rows();
926 const int cols = default_value.cols();
944 template <
typename T>
945 MatrixX<T>
loadParam2(
const std::string& name,
const MatrixX<T>& default_value)
973 template <
int rows,
int cols,
typename T>
976 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>::Zero(), COMPULSORY, UNIQUE);
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)
1002 const auto [ret, loaded_ok] = loadMatrixStatic_internal<rows, cols, T>(name, Eigen::Matrix<T, rows, cols>(default_value), OPTIONAL, UNIQUE);
1023 template <
int rows,
int cols,
typename T =
double>
1026 Eigen::Matrix<T, rows, cols> ret;
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)
1051 Eigen::Matrix<T, rows, cols> ret;
1074 template <
typename T>
1077 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
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)
1101 const auto [ret, loaded_ok] = loadMatrixKnown_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
1120 template <
typename T =
double>
1143 template <
typename T,
typename Derived>
1144 MatrixX<T>
loadMatrixKnown2(
const std::string& name,
const Eigen::MatrixBase<Derived>& default_value,
int rows,
int cols)
1169 template <
typename T>
1172 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(), rows, cols, COMPULSORY, UNIQUE);
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)
1196 const auto [ret, loaded_ok] = loadMatrixDynamic_internal(name, MatrixX<T>(default_value), rows, cols, OPTIONAL, UNIQUE);
1215 template <
typename T =
double>
1238 template <
typename T,
typename Derived>
1239 MatrixX<T>
loadMatrixDynamic2(
const std::string& name,
const Eigen::MatrixBase<Derived>& default_value,
int rows,
int cols)
1281 template <
typename T>
1284 mat = loadMatrixArray2<double>(name);
1298 template <
typename T>
1299 void loadMatrixArray(
const std::string& name, std::vector<MatrixX<T>>& mat,
const std::vector<MatrixX<T>>& default_value)
1314 template <
typename T =
double>
1317 return loadMatrixArray_internal(name, std::vector<MatrixX<T>>(), COMPULSORY, UNIQUE);
1331 template <
typename T>
1332 std::vector<MatrixX<T>>
loadMatrixArray2(
const std::string& name,
const std::vector<MatrixX<T>>& default_value)
1334 return loadMatrixArray_internal(name, default_value, OPTIONAL, UNIQUE);
1353 ros::Duration ParamLoader::loadParam2<ros::Duration>(
const std::string& name,
const ros::Duration& default_value);
1364 ros::Duration ParamLoader::loadParam2<ros::Duration>(
const std::string& name);
1368 #endif // PARAM_LOADER_H