#include <limits>
#include <stdlib.h>
#include <string>
#include <ros/ros.h>
#include <boost/algorithm/string.hpp>
Go to the source code of this file.
Namespaces | |
rosparam_handler | |
Typedefs | |
template<typename T > | |
using | is_map = std::is_same< T, std::map< typename T::key_type, typename T::mapped_type, typename T::key_compare, typename T::allocator_type >> |
Helper function to test for std::map. More... | |
template<typename T > | |
using | is_vector = std::is_same< T, std::vector< typename T::value_type, typename T::allocator_type >> |
Helper function to test for std::vector. More... | |
Functions | |
void | rosparam_handler::exit (const std::string msg="Runtime Error in rosparam handler.") |
ExitFunction for rosparam_handler. More... | |
std::string | rosparam_handler::getNodeName (const ros::NodeHandle &privateNodeHandle) |
Retrieve node name. More... | |
template<typename T > | |
bool | rosparam_handler::getParam (const std::string key, T &val) |
Get parameter from ROS parameter server. More... | |
template<typename T > | |
bool | rosparam_handler::getParam (const std::string key, T &val, const T &defaultValue) |
Get parameter from ROS parameter server or use default value. More... | |
void | rosparam_handler::setLoggerLevel (const ros::NodeHandle &nodeHandle) |
Sets the logger level according to a standardized parameter name 'verbosity'. More... | |
template<typename T > | |
void | rosparam_handler::setParam (const std::string key, T val) |
Set parameter on ROS parameter server. More... | |
void | rosparam_handler::showNodeInfo () |
Show summary about node containing name, namespace, subscribed and advertised topics. More... | |
bool | rosparam_handler::testConstParam (const std::string key) |
Tests that parameter is not set on the parameter server. More... | |
template<typename T > | |
void | rosparam_handler::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 | rosparam_handler::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 | rosparam_handler::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 | rosparam_handler::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 | rosparam_handler::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 | rosparam_handler::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 | rosparam_handler::to_string (const std::vector< T > &v) |
template<typename... T> | |
std::string | rosparam_handler::to_string (const std::map< T... > &map) |
using is_map = std::is_same< T, std::map<typename T::key_type, typename T::mapped_type, typename T::key_compare, typename T::allocator_type>> |
Helper function to test for std::map.
Definition at line 16 of file utilities.hpp.
using is_vector = std::is_same<T, std::vector<typename T::value_type, typename T::allocator_type>> |
Helper function to test for std::vector.
Definition at line 11 of file utilities.hpp.