mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Helper class for ParamLoader. More...
#include <param_provider.h>
Public Member Functions | |
ParamProvider (const ros::NodeHandle &nh, std::string node_name, const bool use_rosparam=true) | |
Main constructor. More... | |
bool | addYamlFile (const std::string &filepath) |
Add a YAML file to be parsed and used for loading parameters. More... | |
template<typename T > | |
bool | getParam (const std::string ¶m_name, T &value_out) const |
Gets the value of a parameter. More... | |
bool | getParam (const std::string ¶m_name, XmlRpc::XmlRpcValue &value_out) const |
Specialization of getParam() for the XmlRpcValue type. More... | |
Helper class for ParamLoader.
This class abstracts away loading of parameters from ROS parameter server and directly from YAML files ("static" parameters). The user can specify a number of YAML files that will be parsed and when a parameter value is requested, these are checked first before attempting to load the parameter from the ROS server (which can be slow). The YAML files are searched in FIFO order and when a matching name is found in a file, its value is returned.
mrs_lib::ParamProvider::ParamProvider | ( | const ros::NodeHandle & | nh, |
std::string | node_name, | ||
const bool | use_rosparam = true |
||
) |
Main constructor.
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. |
use_rosparam | If true, parameters that weren't found in the YAML files will be attempted to be loaded from ROS. |
bool mrs_lib::ParamProvider::addYamlFile | ( | const std::string & | filepath | ) |
Add a YAML file to be parsed and used for loading parameters.
The first file added will be the first file searched for a parameter when using getParam().
filepath | Path to the YAML file. |
bool mrs_lib::ParamProvider::getParam | ( | const std::string & | param_name, |
T & | value_out | ||
) | const |
Gets the value of a parameter.
Firstly, the parameter is attempted to be loaded from the YAML files added by the addYamlFile() method in the same order that they were added. If the parameter is not found in any YAML file, and the use_rosparam flag of the constructor is true, the ParamProvider will attempt to load it from the ROS parameter server.
param_name | Name of the parameter to be loaded. Namespaces should be separated with a forward slash '/'. |
value_out | Output argument that will hold the value of the loaded parameter, if successfull. Not modified otherwise. |
bool mrs_lib::ParamProvider::getParam | ( | const std::string & | param_name, |
XmlRpc::XmlRpcValue & | value_out | ||
) | const |
Specialization of getParam() for the XmlRpcValue type.
The XmlRpc::XmlRpcValue can be useful for manual parsing of more complex types.
param_name | Name of the parameter to be loaded. Namespaces should be separated with a forward slash '/'. |
value_out | Output argument that will hold the value of the loaded parameter, if successfull. Not modified otherwise. |