![]() |
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Helper class for ParamLoader and DynparamMgr. More...
#include <param_provider.h>
Classes | |
struct | declare_options_t |
Struct of options when declaring a parameter to ROS. More... | |
struct | get_options_t |
Struct of options when getting a parameter from ROS. More... | |
struct | range_t |
Helper struct for a numeric range with named members to make the code a bit more readable. More... | |
struct | resolved_name_t |
struct | set_options_t |
Struct of options when setting a parameter to ROS. More... | |
Public Member Functions | |
ParamProvider (const std::shared_ptr< rclcpp::Node > &node, const bool use_rosparam=true) | |
Main constructor. | |
bool | addYamlFile (const std::string &filepath) |
Add a YAML file to be parsed and used for loading parameters. | |
void | copyYamls (const ParamProvider ¶m_provider) |
Copy parsed YAMLs from another ParamProvider. | |
template<typename T > | |
bool | getParam (const std::string ¶m_name, T &value_out) const |
Gets the value of a parameter. | |
template<typename T > | |
bool | getParam (const resolved_name_t &resolved_name, T &value_out, const get_options_t< T > &opts={}) const |
Gets the value of a parameter. | |
template<typename T > | |
bool | setParam (const std::string ¶m_name, const T &value) const |
Sets the value of a parameter to ROS. | |
template<typename T > | |
bool | setParam (const resolved_name_t &resolved_name, const T &value, const set_options_t< T > &opts={}) const |
Sets the value of a parameter to ROS. | |
template<typename T > | |
bool | declareParam (const std::string ¶m_name) const |
Defines a parameter. | |
template<typename T > | |
bool | declareParam (const std::string ¶m_name, const T &default_value) const |
Defines a parameter with a default value. | |
template<typename T > | |
bool | declareParam (const resolved_name_t &resolved_name, const declare_options_t< T > &opts={}) const |
Defines a parameter with various options. | |
void | setPrefix (const std::string &prefix) |
Sets a prefix that will be applied to parameter names before subnode namespaces. | |
std::string | getPrefix () const |
Returns the current parameter name prefix. | |
resolved_name_t | resolveName (const std::string ¶m_name) const |
Returns the parameter name with prefixes and subnode namespaces. | |
Helper class for ParamLoader and DynparamMgr.
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 std::shared_ptr< rclcpp::Node > & | node, |
const bool | use_rosparam = true |
||
) |
Main constructor.
nh | The parameters will be loaded from rosparam using this node handle. |
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. |
void mrs_lib::ParamProvider::copyYamls | ( | const ParamProvider & | param_provider | ) |
Copy parsed YAMLs from another ParamProvider.
param_provider | The ParamProvider object to copy the YAMLs from. |
bool mrs_lib::ParamProvider::declareParam | ( | const resolved_name_t & | resolved_name, |
const declare_options_t< T > & | opts = {} |
||
) | const |
Defines a parameter with various options.
This method declares the parameter in ROS with the behavior controlled by the options allowing to set a default value, valid value range (for numerical types), declare the parameter as reconfigurable, etc.
param_name | Name of the parameter to be loaded. |
opts | Options regarding declaring the parameter (see the declare_options_t<T> documentation). |
bool mrs_lib::ParamProvider::declareParam | ( | const std::string & | param_name | ) | const |
Defines a parameter.
This method only declares the parameter in ROS.
param_name | Name of the parameter to be loaded. |
bool mrs_lib::ParamProvider::declareParam | ( | const std::string & | param_name, |
const T & | default_value | ||
) | const |
Defines a parameter with a default value.
This method declares the parameter in ROS and sets the default value if there is no value in ROS.
param_name | Name of the parameter to be loaded. |
default_value | The default value to be set if there is no value of the parameter. |
bool mrs_lib::ParamProvider::getParam | ( | const resolved_name_t & | resolved_name, |
T & | value_out, | ||
const get_options_t< T > & | opts = {} |
||
) | 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 declare it in ROS and attempt to load it from ROS.
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. |
opts | Options regarding getting and declaring the parameter (see the get_options_t<T> documentation). |
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 declare it in ROS and attempt to load it from ROS.
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. |
std::string mrs_lib::ParamProvider::getPrefix | ( | ) | const |
Returns the current parameter name prefix.
ParamProvider::resolved_name_t mrs_lib::ParamProvider::resolveName | ( | const std::string & | param_name | ) | const |
Returns the parameter name with prefixes and subnode namespaces.
param_name | Name of the parameter. |
bool mrs_lib::ParamProvider::setParam | ( | const resolved_name_t & | resolved_name, |
const T & | value, | ||
const set_options_t< T > & | opts = {} |
||
) | const |
Sets the value of a parameter to ROS.
This method sets the parameter to ROS with the behavior controlled by the options allowing to set a default value, valid value range (for numerical types), declare the parameter as reconfigurable, etc.
param_name | Name of the parameter to be set. Namespaces should be separated with a forward slash '/'. |
value | The desired value of the parameter. |
opts | Options regarding setting and declaring the parameter (see the set_options_t<T> documentation). |
bool mrs_lib::ParamProvider::setParam | ( | const std::string & | param_name, |
const T & | value | ||
) | const |
Sets the value of a parameter to ROS.
This method sets the parameter to ROS with the desired value.
param_name | Name of the parameter to be set. Namespaces should be separated with a forward slash '/'. |
value | The desired value of the parameter. |
void mrs_lib::ParamProvider::setPrefix | ( | const std::string & | prefix | ) |
Sets a prefix that will be applied to parameter names before subnode namespaces.
The prefix will be applied as-is, so if you need to separate it from the parameter name e.g. using a forward slash '/', you must include it in the prefix.
prefix | The prefix to be applied to all parameter names. |