mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
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 ¶m_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 > | |
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 > | |
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 > | |
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 > | |
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... | |
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.
|
inline |
Main constructor.
nh | The parameters will be loaded from rosparam using this node handle. |
printValues | If true, the loaded values will be printed to stdout using std::cout or ROS_INFO if node_name is not empty. |
node_name | Optional node name used when printing the loaded values or loading errors. |
|
inline |
Convenience overload to enable writing ParamLoader pl(nh, node_name);.
nh | The parameters will be loaded from rosparam using this node handle. |
node_name | Optional node name used when printing the loaded values or loading errors. |
|
inline |
Convenience overload to enable writing ParamLoader pl(nh, "node_name");.
nh | The parameters will be loaded from rosparam using this node handle. |
node_name | Optional node name used when printing the loaded values or loading errors. |
|
inline |
Adds the specified file as a source of static parameters.
filepath | The full path to the yaml file to be loaded. |
|
inline |
Loads a filepath from a parameter loads that file as a YAML.
param_name | Name of the parameter from which to load the YAML filename to be loaded. |
|
inline |
Returns the current parameter name prefix.
|
inline |
Indicates whether all compulsory parameters were successfully loaded.
|
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 , where is the common number of rows and is the number of columns of the -th matrix. A typical structure of a yaml
file, specifying the matrix array to be loaded using this method, is
which will be loaded as a std::vector
, containing one matrix and one 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.
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
|
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.
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | The default value to be used in case the parameter is not found on the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | The default value to be used in case the parameter is not found on the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rows | Expected 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). |
cols | Expected 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). |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rows | Expected 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). |
cols | Expected 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). |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rows | Expected 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). |
cols | Expected 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). |
|
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.
name | Name of the parameter in the rosparam server. |
rows | Expected 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). |
cols | Expected 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). |
|
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.
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
|
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.
name | Name of the parameter in the rosparam server. |
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
|
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.
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
|
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.
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
name | Name of the parameter in the rosparam server. |
mat | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
name | Name of the parameter in the rosparam server. |
|
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.
rows | Expected number of rows of the matrix. |
cols | Expected number of columns of the matrix. |
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
out_value | Reference to the variable to which the parameter value will be stored (such as a class member variable). |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
rosparam
, false if the default value was used.
|
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.
name | Name of the parameter in the rosparam server. |
|
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.
name | Name of the parameter in the rosparam server. |
default_value | This value will be used if the parameter name is not found in the rosparam server. |
|
inline |
All loaded parameters will be prefixed with this string.
prefix | the prefix to be applied to all loaded parameters from now on. |