4#include <rclcpp/rclcpp.hpp> 
    6#include <unordered_set> 
    8#include <std_msgs/msg/color_rgba.hpp> 
   22  std::ostream& 
operator<<(std::ostream& os, 
const Eigen::MatrixX<T>& var);
 
   65  using MatrixX = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>;
 
   70  bool                                m_load_successful, m_print_values;
 
   71  std::string                         m_node_name;
 
   72  std::shared_ptr<rclcpp::Node>       m_node;
 
   74  std::unordered_set<resolved_name_t> m_loaded_params;
 
   80  void printError(
const std::string& str);
 
   81  void printWarning(
const std::string& str);
 
  104  template <
typename T>
 
  105  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);
 
  109  template <
int rows, 
int cols, 
typename T>
 
  110  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);
 
  114  template <
typename T>
 
  115  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);
 
  119  template <
typename T>
 
  120  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);
 
  124  template <
typename T>
 
  125  std::vector<MatrixX<T>> loadMatrixArray_internal(
const std::string& name, 
const std::vector<MatrixX<T>>& default_value, optional_t optional, unique_t unique);
 
  142  template <
typename T>
 
  143  std::pair<T, bool> load(
const std::string& name, 
const T& default_value, optional_t optional = OPTIONAL, unique_t unique = UNIQUE);
 
  155  ParamLoader(
const std::shared_ptr<rclcpp::Node>& node, 
bool printValues = 
true, std::string_view node_name = std::string());
 
  164  ParamLoader(
const std::shared_ptr<rclcpp::Node>& node, std::string node_name);
 
  178  void setPrefix(
const std::string& prefix);
 
  265  template <
typename T>
 
  266  bool loadParam(
const std::string& name, T& out_value, 
const T& default_value);
 
  279  template <
typename T>
 
  280  T 
loadParam2(
const std::string& name, 
const T& default_value);
 
  294  template <
typename T>
 
  295  bool loadParamReusable(
const std::string& name, T& out_value, 
const T& default_value);
 
  308  template <
typename T>
 
  325  template <
typename T>
 
  326  bool loadParam(
const std::string& name, T& out_value); 
 
  338  template <
typename T>
 
  352  template <
typename T>
 
  365  template <
typename T>
 
  382  bool loadParam(
const std::string& name, rclcpp::Duration& out, 
const rclcpp::Duration& default_value);
 
  393  bool loadParam(
const std::string& name, rclcpp::Duration& out);
 
  409  bool loadParam(
const std::string& name, std_msgs::msg::ColorRGBA& out, 
const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
 
  420  std_msgs::msg::ColorRGBA 
loadParam2(
const std::string& name, 
const std_msgs::msg::ColorRGBA& default_value = std_msgs::msg::ColorRGBA());
 
  440  template <
typename T>
 
  441  bool loadParam(
const std::string& name, MatrixX<T>& mat, 
const MatrixX<T>& default_value);
 
  456  template <
typename T>
 
  457  MatrixX<T> 
loadParam2(
const std::string& name, 
const MatrixX<T>& default_value);
 
  480  template <
int rows, 
int cols, 
typename T>
 
  481  bool loadMatrixStatic(
const std::string& name, Eigen::Matrix<T, rows, cols>& mat);
 
  500  template <
int rows, 
int cols, 
typename T, 
typename Derived>
 
  501  bool loadMatrixStatic(
const std::string& name, Eigen::Matrix<T, rows, cols>& mat, 
const Eigen::MatrixBase<Derived>& default_value);
 
  519  template <
int rows, 
int cols, 
typename T = 
double>
 
  538  template <
int rows, 
int cols, 
typename T, 
typename Derived>
 
  539  Eigen::Matrix<T, rows, cols> 
loadMatrixStatic2(
const std::string& name, 
const Eigen::MatrixBase<Derived>& default_value);
 
  560  template <
typename T>
 
  561  bool loadMatrixKnown(
const std::string& name, MatrixX<T>& mat, 
int rows, 
int cols);
 
  578  template <
typename T, 
typename Derived>
 
  579  bool loadMatrixKnown(
const std::string& name, MatrixX<T>& mat, 
const Eigen::MatrixBase<Derived>& default_value, 
int rows, 
int cols);
 
  595  template <
typename T = 
double>
 
  612  template <
typename T, 
typename Derived>
 
  613  MatrixX<T> 
loadMatrixKnown2(
const std::string& name, 
const Eigen::MatrixBase<Derived>& default_value, 
int rows, 
int cols);
 
  634  template <
typename T>
 
  635  bool loadMatrixDynamic(
const std::string& name, MatrixX<T>& mat, 
int rows, 
int cols);
 
  653  template <
typename T, 
typename Derived>
 
  654  bool loadMatrixDynamic(
const std::string& name, MatrixX<T>& mat, 
const Eigen::MatrixBase<Derived>& default_value, 
int rows, 
int cols);
 
  670  template <
typename T = 
double>
 
  687  template <
typename T, 
typename Derived>
 
  688  MatrixX<T> 
loadMatrixDynamic2(
const std::string& name, 
const Eigen::MatrixBase<Derived>& default_value, 
int rows, 
int cols);
 
  725  template <
typename T>
 
  726  void loadMatrixArray(
const std::string& name, std::vector<MatrixX<T>>& mat);
 
  739  template <
typename T>
 
  740  void loadMatrixArray(
const std::string& name, std::vector<MatrixX<T>>& mat, 
const std::vector<MatrixX<T>>& default_value);
 
  752  template <
typename T = 
double>
 
  766  template <
typename T>
 
  767  std::vector<MatrixX<T>> 
loadMatrixArray2(
const std::string& name, 
const std::vector<MatrixX<T>>& default_value);
 
 
  784rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(
const std::string& name, 
const rclcpp::Duration& default_value);
 
  795rclcpp::Duration ParamLoader::loadParam2<rclcpp::Duration>(
const std::string& name);
 
  799#include <mrs_lib/impl/param_loader.hpp> 
Convenience class for loading parameters from rosparam server.
Definition param_loader.h:45
void copyYamls(const ParamLoader ¶m_loader)
Copies parsed YAMLs from another ParamLoader.
Definition param_loader.cpp:135
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
void resetLoadedSuccessfully()
Resets the loadedSuccessfully flag back to true.
Definition param_loader.cpp:112
bool loadedSuccessfully() const
Indicates whether all compulsory parameters were successfully loaded.
Definition param_loader.cpp:107
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
bool addYamlFileFromParam(const std::string ¶m_name)
Loads a filepath from a parameter loads that file as a YAML.
Definition param_loader.cpp:127
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
std::string getPrefix()
Returns the current parameter name prefix.
Definition param_loader.cpp:102
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
bool addYamlFile(const std::string &filepath)
Adds the specified file as a source of static parameters.
Definition param_loader.cpp:122
void setPrefix(const std::string &prefix)
Sets a prefix that will be applied to parameter names before subnode namespaces.
Definition param_loader.cpp:97
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
ParamProvider & getParamProvider()
Returns the internal ParamProvider object.
Definition param_loader.cpp:140
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
void resetUniques()
Resets the list of already loaded parameter names used when checking for uniqueness.
Definition param_loader.cpp:117
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:42