mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib::ParamLoader Class Reference

Convenience class for loading parameters from rosparam server. More...

#include <param_loader.h>

Public Member Functions

 ParamLoader (const ros::NodeHandle &nh, bool printValues=true, std::string_view node_name=std::string())
 Main constructor. More...
 
 ParamLoader (const ros::NodeHandle &nh, std::string_view node_name)
 Convenience overload to enable writing ParamLoader pl(nh, node_name);. More...
 
 ParamLoader (const std::string &filepath, const ros::NodeHandle &nh)
 Convenience overload to enable writing ParamLoader pl(nh, "node_name");. More...
 
void setPrefix (const std::string &prefix)
 All loaded parameters will be prefixed with this string. More...
 
std::string getPrefix ()
 Returns the current parameter name prefix. More...
 
bool addYamlFile (const std::string &filepath)
 Adds the specified file as a source of static parameters. More...
 
bool addYamlFileFromParam (const std::string &param_name)
 Loads a filepath from a parameter loads that file as a YAML. More...
 
bool loadedSuccessfully ()
 Indicates whether all compulsory parameters were successfully loaded. More...
 
void resetLoadedSuccessfully ()
 Resets the loadedSuccessfully flag back to true.
 
void resetUniques ()
 Resets the list of already loaded parameter names used when checking for uniqueness.
 
template<typename T >
bool loadParam (const std::string &name, T &out_value, const T &default_value)
 Loads a parameter from the rosparam server with a default value. More...
 
template<typename T >
loadParam2 (const std::string &name, const T &default_value)
 Loads a parameter from the rosparam server with a default value. More...
 
template<typename T >
bool loadParamReusable (const std::string &name, T &out_value, const T &default_value)
 Loads a parameter from the rosparam server with a default value. More...
 
template<typename T >
loadParamReusable2 (const std::string &name, const T &default_value)
 Loads an optional reusable parameter from the rosparam server. More...
 
template<typename T >
bool loadParam (const std::string &name, T &out_value)
 Loads a compulsory parameter from the rosparam server. More...
 
template<typename T >
loadParam2 (const std::string &name)
 Loads a compulsory parameter from the rosparam server. More...
 
template<typename T >
bool loadParamReusable (const std::string &name, T &out_value)
 Loads a compulsory parameter from the rosparam server. More...
 
template<typename T >
loadParamReusable2 (const std::string &name)
 Loads a compulsory parameter from the rosparam server. More...
 
bool loadParam (const std::string &name, ros::Duration &out, const ros::Duration &default_value)
 An overload for loading ros::Duration. More...
 
bool loadParam (const std::string &name, ros::Duration &out)
 An overload for loading ros::Duration. More...
 
bool loadParam (const std::string &name, std_msgs::ColorRGBA &out, const std_msgs::ColorRGBA &default_value={})
 An overload for loading std_msgs::ColorRGBA. More...
 
std_msgs::ColorRGBA loadParam2 (const std::string &name, const std_msgs::ColorRGBA &default_value={})
 An overload for loading std_msgs::ColorRGBA. More...
 
bool loadParam (const std::string &name, XmlRpc::XmlRpcValue &out, const XmlRpc::XmlRpcValue &default_value)
 An overload for loading an optional XmlRpc::XmlRpcValue. More...
 
bool loadParam (const std::string &name, XmlRpc::XmlRpcValue &out)
 An overload for loading a compulsory XmlRpc::XmlRpcValue. More...
 
XmlRpc::XmlRpcValue loadParam2 (const std::string &name, const XmlRpc::XmlRpcValue &default_value)
 An overload for loading an optional XmlRpc::XmlRpcValue. More...
 
template<typename T >
bool loadParam (const std::string &name, MatrixX< T > &mat, const MatrixX< T > &default_value)
 An overload for loading Eigen matrices. More...
 
template<typename T >
MatrixX< T > loadParam2 (const std::string &name, const MatrixX< T > &default_value)
 An overload for loading Eigen matrices. More...
 
template<int rows, int cols, typename T >
bool loadMatrixStatic (const std::string &name, Eigen::Matrix< T, rows, cols > &mat)
 Specialized method for loading compulsory Eigen matrix parameters. More...
 
template<int rows, int cols, typename T , typename Derived >
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. More...
 
template<int rows, int cols, typename T = double>
Eigen::Matrix< T, rows, cols > loadMatrixStatic2 (const std::string &name)
 Specialized method for loading compulsory Eigen matrix parameters. More...
 
template<int rows, int cols, typename T , typename Derived >
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. More...
 
template<typename T >
bool loadMatrixKnown (const std::string &name, MatrixX< T > &mat, int rows, int cols)
 Specialized method for loading compulsory Eigen matrix parameters. More...
 
template<typename T , typename Derived >
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. More...
 
template<typename T = double>
MatrixX< T > loadMatrixKnown2 (const std::string &name, int rows, int cols)
 Specialized method for loading compulsory Eigen matrix parameters. More...
 
template<typename T , typename Derived >
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. More...
 
template<typename T >
bool loadMatrixDynamic (const std::string &name, MatrixX< T > &mat, int rows, int cols)
 Specialized method for loading compulsory dynamic Eigen matrix parameters. More...
 
template<typename T , typename Derived >
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. More...
 
template<typename T = double>
MatrixX< T > loadMatrixDynamic2 (const std::string &name, int rows, int cols)
 Specialized method for loading compulsory dynamic Eigen matrix parameters. More...
 
template<typename T , typename Derived >
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. More...
 
template<typename T >
void loadMatrixArray (const std::string &name, std::vector< MatrixX< T >> &mat)
 Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices. More...
 
template<typename T >
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 matrices. More...
 
template<typename T = double>
std::vector< MatrixX< T > > loadMatrixArray2 (const std::string &name)
 Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices. More...
 
template<typename T >
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 matrices. More...
 

Detailed Description

Convenience class for loading parameters from rosparam server.

The parameters can be loaded as compulsory. If a compulsory parameter is not found on the rosparam server (e.g. because it is missing in the launchfile or the yaml config file), an internal flag is set to false, indicating that the parameter loading procedure failed. This flag can be checked using the loaded_successfully() method after all parameters were attempted to be loaded (see usage example usage below).

The loaded parameter names and corresponding values are printed to stdout by default for user convenience. Special cases such as loading of Eigen matrices or loading of std::vectors of various values are also provided.

To load parameters into the rosparam server, use a launchfile prefferably. See documentation of ROS launchfiles here: http://wiki.ros.org/roslaunch/XML. Specifically, the param XML tag is used for loading parameters directly from the launchfile: http://wiki.ros.org/roslaunch/XML/param, and the rosparam XML tag tag is used for loading parameters from a yaml file: http://wiki.ros.org/roslaunch/XML/rosparam.

Examples
param_loader/example.cpp.

Constructor & Destructor Documentation

◆ ParamLoader() [1/3]

mrs_lib::ParamLoader::ParamLoader ( const ros::NodeHandle &  nh,
bool  printValues = true,
std::string_view  node_name = std::string() 
)
inline

Main constructor.

Parameters
nhThe parameters will be loaded from rosparam using this node handle.
printValuesIf true, the loaded values will be printed to stdout using std::cout or ROS_INFO if node_name is not empty.
node_nameOptional node name used when printing the loaded values or loading errors.

◆ ParamLoader() [2/3]

mrs_lib::ParamLoader::ParamLoader ( const ros::NodeHandle &  nh,
std::string_view  node_name 
)
inline

Convenience overload to enable writing ParamLoader pl(nh, node_name);.

Parameters
nhThe parameters will be loaded from rosparam using this node handle.
node_nameOptional node name used when printing the loaded values or loading errors.

◆ ParamLoader() [3/3]

mrs_lib::ParamLoader::ParamLoader ( const std::string &  filepath,
const ros::NodeHandle &  nh 
)
inline

Convenience overload to enable writing ParamLoader pl(nh, "node_name");.

Parameters
nhThe parameters will be loaded from rosparam using this node handle.
node_nameOptional node name used when printing the loaded values or loading errors.

Member Function Documentation

◆ addYamlFile()

bool mrs_lib::ParamLoader::addYamlFile ( const std::string &  filepath)
inline

Adds the specified file as a source of static parameters.

Parameters
filepathThe full path to the yaml file to be loaded.
Returns
true if loading and parsing the file was successful, false otherwise.
Examples
param_loader/example.cpp.

◆ addYamlFileFromParam()

bool mrs_lib::ParamLoader::addYamlFileFromParam ( const std::string &  param_name)
inline

Loads a filepath from a parameter loads that file as a YAML.

Parameters
param_nameName of the parameter from which to load the YAML filename to be loaded.
Returns
true if loading and parsing the file was successful, false otherwise.

◆ getPrefix()

std::string mrs_lib::ParamLoader::getPrefix ( )
inline

Returns the current parameter name prefix.

Returns
the current prefix to be applied to the loaded parameters.

◆ loadedSuccessfully()

bool mrs_lib::ParamLoader::loadedSuccessfully ( )
inline

Indicates whether all compulsory parameters were successfully loaded.

Returns
false if any compulsory parameter was not loaded (is not present at rosparam server). Otherwise returns true.
Examples
param_loader/example.cpp.

◆ loadMatrixArray() [1/2]

template<typename T >
void mrs_lib::ParamLoader::loadMatrixArray ( const std::string &  name,
std::vector< MatrixX< T >> &  mat 
)
inline

Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices.

The number of rows and columns of the matrices to be loaded is specified in the rosparam parameter. Specifically, the name/rows value specifies the number of rows, which must be common to all the loaded matrices (i.e. it is one integer >= 0), and the name/cols value specifies the number of columns of each matrix (i.e. it is an array of integers > 0). The name/data array contains the values of the elements of the matrices and it must have length $ r\sum_i c_i $, where $ r $ is the common number of rows and $ c_i $ is the number of columns of the $ i $-th matrix. A typical structure of a yaml file, specifying the matrix array to be loaded using this method, is

matrix_array:
rows: 3
cols: [1, 2]
data: [-5.0, 0.0, 23.0,
-5.0, 0.0, 12.0,
2.0, 4.0, 7.0]

which will be loaded as a std::vector, containing one $ 3\times 1 $ matrix and one $ 3\times 2 $ matrix.

If the dimensions of the loaded matrices do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).

◆ loadMatrixArray() [2/2]

template<typename T >
void mrs_lib::ParamLoader::loadMatrixArray ( const std::string &  name,
std::vector< MatrixX< T >> &  mat,
const std::vector< MatrixX< T >> &  default_value 
)
inline

Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices.

This overload of the loadMatrixArray() method takes a default value for the parameter, which is used in case a rosparam with the specified name is not found in the rosparam server, instead of causing an unsuccessful load. This makes specifying the parameter value in the rosparam server optional.

Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThe default value to be used in case the parameter is not found on the rosparam server.

◆ loadMatrixArray2() [1/2]

template<typename T = double>
std::vector<MatrixX<T> > mrs_lib::ParamLoader::loadMatrixArray2 ( const std::string &  name)
inline

Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices.

This method works in the same way as the loadMatrixArray() method for compulsory parameters, except that the loaded parameter is returned and not stored in the reference parameter.

Parameters
nameName of the parameter in the rosparam server.
Returns
The loaded parameter or a default constructed object of the respective type.

◆ loadMatrixArray2() [2/2]

template<typename T >
std::vector<MatrixX<T> > mrs_lib::ParamLoader::loadMatrixArray2 ( const std::string &  name,
const std::vector< MatrixX< T >> &  default_value 
)
inline

Specialized method for loading compulsory parameters, interpreted as an array of dynamic Eigen matrices.

This method works in the same way as the loadMatrixArray() method for optional parameters, except that the loaded parameter is returned and not stored in the reference parameter.

Parameters
nameName of the parameter in the rosparam server.
default_valueThe default value to be used in case the parameter is not found on the rosparam server.
Returns
The loaded parameter or the default value.

◆ loadMatrixDynamic() [1/2]

template<typename T , typename Derived >
bool mrs_lib::ParamLoader::loadMatrixDynamic ( const std::string &  name,
MatrixX< T > &  mat,
const Eigen::MatrixBase< Derived > &  default_value,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory dynamic Eigen matrix parameters.

This variant assumes that the only one of the matrix dimensions are known, the other is selected based on the loaded value. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
rowsExpected number of rows of the matrix (negative value indicates that the number of rows is to be deduced from the specified number of columns and the size of the loaded array).
colsExpected number of columns of the matrix (negative value indicates that the number of columns is to be deduced from the specified number of rows and the size of the loaded array).
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadMatrixDynamic() [2/2]

template<typename T >
bool mrs_lib::ParamLoader::loadMatrixDynamic ( const std::string &  name,
MatrixX< T > &  mat,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory dynamic Eigen matrix parameters.

This variant assumes that the only one of the matrix dimensions are known, the other is selected based on the loaded value. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
rowsExpected number of rows of the matrix (negative value indicates that the number of rows is to be deduced from the specified number of columns and the size of the loaded array).
colsExpected number of columns of the matrix (negative value indicates that the number of columns is to be deduced from the specified number of rows and the size of the loaded array).
Returns
true if loaded successfully, false otherwise.
Examples
param_loader/example.cpp.

◆ loadMatrixDynamic2() [1/2]

template<typename T , typename Derived >
MatrixX<T> mrs_lib::ParamLoader::loadMatrixDynamic2 ( const std::string &  name,
const Eigen::MatrixBase< Derived > &  default_value,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory dynamic Eigen matrix parameters.

This variant assumes that the only one of the matrix dimensions are known, the other is selected based on the loaded value. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
rowsExpected number of rows of the matrix (negative value indicates that the number of rows is to be deduced from the specified number of columns and the size of the loaded array).
colsExpected number of columns of the matrix (negative value indicates that the number of columns is to be deduced from the specified number of rows and the size of the loaded array).
Returns
The loaded parameter value.

◆ loadMatrixDynamic2() [2/2]

template<typename T = double>
MatrixX<T> mrs_lib::ParamLoader::loadMatrixDynamic2 ( const std::string &  name,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory dynamic Eigen matrix parameters.

This variant assumes that the only one of the matrix dimensions are known, the other is selected based on the loaded value. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
rowsExpected number of rows of the matrix (negative value indicates that the number of rows is to be deduced from the specified number of columns and the size of the loaded array).
colsExpected number of columns of the matrix (negative value indicates that the number of columns is to be deduced from the specified number of rows and the size of the loaded array).
Returns
The loaded parameter value.

◆ loadMatrixKnown() [1/2]

template<typename T , typename Derived >
bool mrs_lib::ParamLoader::loadMatrixKnown ( const std::string &  name,
MatrixX< T > &  mat,
const Eigen::MatrixBase< Derived > &  default_value,
int  rows,
int  cols 
)
inline

Specialized method for loading Eigen matrix parameters with default value.

This variant assumes that the matrix dimensions are known in runtime, but not compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadMatrixKnown() [2/2]

template<typename T >
bool mrs_lib::ParamLoader::loadMatrixKnown ( const std::string &  name,
MatrixX< T > &  mat,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory Eigen matrix parameters.

This variant assumes that the matrix dimensions are known in runtime, but not compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Returns
true if loaded successfully, false otherwise.

◆ loadMatrixKnown2() [1/2]

template<typename T , typename Derived >
MatrixX<T> mrs_lib::ParamLoader::loadMatrixKnown2 ( const std::string &  name,
const Eigen::MatrixBase< Derived > &  default_value,
int  rows,
int  cols 
)
inline

Specialized method for loading Eigen matrix parameters with default value.

This variant assumes that the matrix dimensions are known in runtime, but not compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Returns
The loaded parameter value.

◆ loadMatrixKnown2() [2/2]

template<typename T = double>
MatrixX<T> mrs_lib::ParamLoader::loadMatrixKnown2 ( const std::string &  name,
int  rows,
int  cols 
)
inline

Specialized method for loading compulsory Eigen matrix parameters.

This variant assumes that the matrix dimensions are known in runtime, but not compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Returns
The loaded parameter value.

◆ loadMatrixStatic() [1/2]

template<int rows, int cols, typename T >
bool mrs_lib::ParamLoader::loadMatrixStatic ( const std::string &  name,
Eigen::Matrix< T, rows, cols > &  mat 
)
inline

Specialized method for loading compulsory Eigen matrix parameters.

This variant assumes that the matrix dimensions are known in compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Template Parameters
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
Returns
true if loaded successfully, false otherwise.

◆ loadMatrixStatic() [2/2]

template<int rows, int cols, typename T , typename Derived >
bool mrs_lib::ParamLoader::loadMatrixStatic ( const std::string &  name,
Eigen::Matrix< T, rows, cols > &  mat,
const Eigen::MatrixBase< Derived > &  default_value 
)
inline

Specialized method for loading Eigen matrix parameters with default value.

This variant assumes that the matrix dimensions are known in compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Template Parameters
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Parameters
nameName of the parameter in the rosparam server.
matReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadMatrixStatic2() [1/2]

template<int rows, int cols, typename T = double>
Eigen::Matrix<T, rows, cols> mrs_lib::ParamLoader::loadMatrixStatic2 ( const std::string &  name)
inline

Specialized method for loading compulsory Eigen matrix parameters.

This variant assumes that the matrix dimensions are known in compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Template Parameters
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Parameters
nameName of the parameter in the rosparam server.
Returns
The loaded parameter value.

◆ loadMatrixStatic2() [2/2]

template<int rows, int cols, typename T , typename Derived >
Eigen::Matrix<T, rows, cols> mrs_lib::ParamLoader::loadMatrixStatic2 ( const std::string &  name,
const Eigen::MatrixBase< Derived > &  default_value 
)
inline

Specialized method for loading Eigen matrix parameters with default value.

This variant assumes that the matrix dimensions are known in compiletime. If the dimensions of the loaded matrix do not match the specified number of rows and columns, the loading process is unsuccessful (loaded_successfully() will return false). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Template Parameters
rowsExpected number of rows of the matrix.
colsExpected number of columns of the matrix.
Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.

◆ loadParam() [1/8]

template<typename T >
bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
MatrixX< T > &  mat,
const MatrixX< T > &  default_value 
)
inline

An overload for loading Eigen matrices.

Matrix dimensions are deduced from the provided default value. For compulsory Eigen matrices, use loadMatrixStatic(), loadMatrixKnown() or loadMatrixDynamic(). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
True if loaded successfully, false otherwise.

◆ loadParam() [2/8]

bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
ros::Duration &  out 
)
inline

An overload for loading ros::Duration.

The duration will be loaded as a double, representing a number of seconds, and then converted to ros::Duration.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam() [3/8]

bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
ros::Duration &  out,
const ros::Duration &  default_value 
)
inline

An overload for loading ros::Duration.

The duration will be loaded as a double, representing a number of seconds, and then converted to ros::Duration.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam() [4/8]

bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
std_msgs::ColorRGBA &  out,
const std_msgs::ColorRGBA &  default_value = {} 
)
inline

An overload for loading std_msgs::ColorRGBA.

The color will be loaded as several double -typed variables, representing the R, G, B and A color elements.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam() [5/8]

template<typename T >
bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
T &  out_value 
)
inline

Loads a compulsory parameter from the rosparam server.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful (loaded_successfully() will return false). Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam() [6/8]

template<typename T >
bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
T &  out_value,
const T &  default_value 
)
inline

Loads a parameter from the rosparam server with a default value.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.
Examples
param_loader/example.cpp.

◆ loadParam() [7/8]

bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
XmlRpc::XmlRpcValue &  out 
)
inline

An overload for loading a compulsory XmlRpc::XmlRpcValue.

This can be used if you want to manually parse some more complex parameter but still take advantage of ParamLoader.

Warning
XmlRpc::XmlRpcValue must be loaded from a rosparam server and not directly from a YAML file (i.e. you cannot use it to load parameters from a file added using the addYamlFile() or addYamlFileFromParam() methods).
Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam() [8/8]

bool mrs_lib::ParamLoader::loadParam ( const std::string &  name,
XmlRpc::XmlRpcValue &  out,
const XmlRpc::XmlRpcValue &  default_value 
)
inline

An overload for loading an optional XmlRpc::XmlRpcValue.

This can be used if you want to manually parse some more complex parameter but still take advantage of ParamLoader.

Warning
XmlRpc::XmlRpcValue must be loaded from a rosparam server and not directly from a YAML file (i.e. you cannot use it to load parameters from a file added using the addYamlFile() or addYamlFileFromParam() methods).
Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParam2() [1/5]

template<typename T >
T mrs_lib::ParamLoader::loadParam2 ( const std::string &  name)
inline

Loads a compulsory parameter from the rosparam server.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful (loaded_successfully() will return false). Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
Returns
The loaded parameter value.

◆ loadParam2() [2/5]

template<typename T >
MatrixX<T> mrs_lib::ParamLoader::loadParam2 ( const std::string &  name,
const MatrixX< T > &  default_value 
)
inline

An overload for loading Eigen matrices.

Matrix dimensions are deduced from the provided default value. For compulsory Eigen matrices, use loadMatrixStatic(), loadMatrixKnown() or loadMatrixDynamic(). If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.

◆ loadParam2() [3/5]

std_msgs::ColorRGBA mrs_lib::ParamLoader::loadParam2 ( const std::string &  name,
const std_msgs::ColorRGBA &  default_value = {} 
)
inline

An overload for loading std_msgs::ColorRGBA.

The color will be loaded as several double -typed variables, representing the R, G, B and A color elements.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.

◆ loadParam2() [4/5]

template<typename T >
T mrs_lib::ParamLoader::loadParam2 ( const std::string &  name,
const T &  default_value 
)
inline

Loads a parameter from the rosparam server with a default value.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can only be loaded once using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.
Examples
param_loader/example.cpp.

◆ loadParam2() [5/5]

XmlRpc::XmlRpcValue mrs_lib::ParamLoader::loadParam2 ( const std::string &  name,
const XmlRpc::XmlRpcValue &  default_value 
)
inline

An overload for loading an optional XmlRpc::XmlRpcValue.

This can be used if you want to manually parse some more complex parameter but still take advantage of ParamLoader.

Warning
XmlRpc::XmlRpcValue must be loaded from a rosparam server and not directly from a YAML file (i.e. you cannot use it to load parameters from a file added using the addYamlFile() or addYamlFileFromParam() methods).
Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
the loaded parameter.

◆ loadParamReusable() [1/2]

template<typename T >
bool mrs_lib::ParamLoader::loadParamReusable ( const std::string &  name,
T &  out_value 
)
inline

Loads a compulsory parameter from the rosparam server.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful (loaded_successfully() will return false). Using this method, the parameter can be loaded multiple times using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParamReusable() [2/2]

template<typename T >
bool mrs_lib::ParamLoader::loadParamReusable ( const std::string &  name,
T &  out_value,
const T &  default_value 
)
inline

Loads a parameter from the rosparam server with a default value.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can be loaded multiple times using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
out_valueReference to the variable to which the parameter value will be stored (such as a class member variable).
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
true if the parameter was loaded from rosparam, false if the default value was used.

◆ loadParamReusable2() [1/2]

template<typename T >
T mrs_lib::ParamLoader::loadParamReusable2 ( const std::string &  name)
inline

Loads a compulsory parameter from the rosparam server.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the loading process is unsuccessful (loaded_successfully() will return false). Using this method, the parameter can be loaded multiple times using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
Returns
The loaded parameter value.

◆ loadParamReusable2() [2/2]

template<typename T >
T mrs_lib::ParamLoader::loadParamReusable2 ( const std::string &  name,
const T &  default_value 
)
inline

Loads an optional reusable parameter from the rosparam server.

If the parameter with the specified name is not found on the rosparam server (e.g. because it is not specified in the launchfile or yaml config file), the default value is used. Using this method, the parameter can be loaded multiple times using the same ParamLoader instance without error.

Parameters
nameName of the parameter in the rosparam server.
default_valueThis value will be used if the parameter name is not found in the rosparam server.
Returns
The loaded parameter value.

◆ setPrefix()

void mrs_lib::ParamLoader::setPrefix ( const std::string &  prefix)
inline

All loaded parameters will be prefixed with this string.

Parameters
prefixthe prefix to be applied to all loaded parameters from now on.

The documentation for this class was generated from the following file: