16 #ifndef PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H 17 #define PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H 21 #include <boost/optional.hpp> 34 ROS_WARN_STREAM(
"Parameter " + key +
" doesn't exist on parameter server.");
39 boost::optional<T> ret_val(default_val);
40 if (!node_handle.
getParam(key, ret_val.get()))
42 throw WrongParameterType(
"Parameter " + key +
" has wrong datatype on parameter server.");
50 boost::optional<T> val{ getParam<T>(node_handle, key) };
61 boost::optional<T> val{ getParam<T>(node_handle, key) };
71 #endif // PSEN_SCAN_V2_ROS_PARAMETER_HANDLER_H
boost::optional< T > getParam(const ros::NodeHandle &node_handle, const std::string &key)
T getRequiredParamFromServer(const ros::NodeHandle &node_handle, const std::string &key)
bool getParam(const std::string &key, std::string &s) const
Root namespace for the ROS part.
#define ROS_WARN_STREAM(args)
bool hasParam(const std::string &key) const
T getOptionalParamFromServer(const ros::NodeHandle &node_handle, const std::string &key, const T &default_value)
Exception thrown if a parameter of a certain type cannot be found on the ROS parameter server...
Exception thrown if a parameter can be found on the ROS parameter server but with an unexpected type...