Namespaces | Functions
rosparam_handler Namespace Reference

Namespaces

 parameter_generator_catkin
 

Functions

void exit (const std::string msg="Runtime Error in rosparam handler.")
 ExitFunction for rosparam_handler. More...
 
std::string getNodeName (const ros::NodeHandle &privateNodeHandle)
 Retrieve node name. More...
 
template<typename T >
bool getParam (const std::string key, T &val)
 Get parameter from ROS parameter server. More...
 
template<typename T >
bool getParam (const std::string key, T &val, const T &defaultValue)
 Get parameter from ROS parameter server or use default value. More...
 
void setLoggerLevel (const ros::NodeHandle &nodeHandle)
 Sets the logger level according to a standardized parameter name 'verbosity'. More...
 
template<typename T >
void setParam (const std::string key, T val)
 Set parameter on ROS parameter server. More...
 
void showNodeInfo ()
 Show summary about node containing name, namespace, subscribed and advertised topics. More...
 
bool testConstParam (const std::string key)
 Tests that parameter is not set on the parameter server. More...
 
template<typename T >
void testMax (const std::string key, T &val, T max=std::numeric_limits< T >::max())
 Limit parameter to upper bound if parameter is a scalar. More...
 
template<typename T >
void testMax (const std::string key, std::vector< T > &val, T max=std::numeric_limits< T >::max())
 Limit parameter to upper bound if parameter is a vector. More...
 
template<typename K , typename T >
void testMax (const std::string key, std::map< K, T > &val, T max=std::numeric_limits< T >::max())
 Limit parameter to upper bound if parameter is a map. More...
 
template<typename T >
void testMin (const std::string key, T &val, T min=std::numeric_limits< T >::min())
 Limit parameter to lower bound if parameter is a scalar. More...
 
template<typename T >
void testMin (const std::string key, std::vector< T > &val, T min=std::numeric_limits< T >::min())
 Limit parameter to lower bound if parameter is a vector. More...
 
template<typename K , typename T >
void testMin (const std::string key, std::map< K, T > &val, T min=std::numeric_limits< T >::min())
 Limit parameter to lower bound if parameter is a map. More...
 
template<typename T >
std::string to_string (const std::vector< T > &v)
 
template<typename... T>
std::string to_string (const std::map< T... > &map)
 

Function Documentation

void rosparam_handler::exit ( const std::string  msg = "Runtime Error in rosparam handler.")
inline

ExitFunction for rosparam_handler.

Definition at line 119 of file utilities.hpp.

std::string rosparam_handler::getNodeName ( const ros::NodeHandle privateNodeHandle)
inline

Retrieve node name.

Parameters
privateNodeHandleThe private ROS node handle (i.e. ros::NodeHandle("~") ).
Returns
node name

Definition at line 108 of file utilities.hpp.

template<typename T >
bool rosparam_handler::getParam ( const std::string  key,
T &  val 
)
inline

Get parameter from ROS parameter server.

Parameters
keyParameter name
valParameter value

Definition at line 138 of file utilities.hpp.

template<typename T >
bool rosparam_handler::getParam ( const std::string  key,
T &  val,
const T &  defaultValue 
)
inline

Get parameter from ROS parameter server or use default value.

If parameter does not exist on server yet, the default value is used and set on server.

Parameters
keyParameter name
valParameter value
defaultValueParameter default value

Definition at line 157 of file utilities.hpp.

void rosparam_handler::setLoggerLevel ( const ros::NodeHandle nodeHandle)
inline

Sets the logger level according to a standardized parameter name 'verbosity'.

Parameters
nodeHandleThe ROS node handle to search for the parameter 'verbosity'.

Definition at line 49 of file utilities.hpp.

template<typename T >
void rosparam_handler::setParam ( const std::string  key,
val 
)
inline

Set parameter on ROS parameter server.

Parameters
keyParameter name
valParameter value

Definition at line 129 of file utilities.hpp.

void rosparam_handler::showNodeInfo ( )
inline

Show summary about node containing name, namespace, subscribed and advertised topics.

Definition at line 81 of file utilities.hpp.

bool rosparam_handler::testConstParam ( const std::string  key)
inline

Tests that parameter is not set on the parameter server.

Definition at line 170 of file utilities.hpp.

template<typename T >
void rosparam_handler::testMax ( const std::string  key,
T &  val,
max = std::numeric_limits<T>::max() 
)
inline

Limit parameter to upper bound if parameter is a scalar.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 222 of file utilities.hpp.

template<typename T >
void rosparam_handler::testMax ( const std::string  key,
std::vector< T > &  val,
max = std::numeric_limits<T>::max() 
)
inline

Limit parameter to upper bound if parameter is a vector.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 236 of file utilities.hpp.

template<typename K , typename T >
void rosparam_handler::testMax ( const std::string  key,
std::map< K, T > &  val,
max = std::numeric_limits<T>::max() 
)
inline

Limit parameter to upper bound if parameter is a map.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 247 of file utilities.hpp.

template<typename T >
void rosparam_handler::testMin ( const std::string  key,
T &  val,
min = std::numeric_limits<T>::min() 
)
inline

Limit parameter to lower bound if parameter is a scalar.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 186 of file utilities.hpp.

template<typename T >
void rosparam_handler::testMin ( const std::string  key,
std::vector< T > &  val,
min = std::numeric_limits<T>::min() 
)
inline

Limit parameter to lower bound if parameter is a vector.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 200 of file utilities.hpp.

template<typename K , typename T >
void rosparam_handler::testMin ( const std::string  key,
std::map< K, T > &  val,
min = std::numeric_limits<T>::min() 
)
inline

Limit parameter to lower bound if parameter is a map.

Parameters
keyParameter name
valParameter value
minLower Threshold

Definition at line 211 of file utilities.hpp.

template<typename T >
std::string rosparam_handler::to_string ( const std::vector< T > &  v)
inline

Definition at line 21 of file utilities.hpp.

template<typename... T>
std::string rosparam_handler::to_string ( const std::map< T... > &  map)
inline

Definition at line 35 of file utilities.hpp.



rosparam_handler
Author(s): Claudio Bandera
autogenerated on Mon Jun 10 2019 14:48:10