Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016 #ifndef PARAMETER_SERVER_H_
00017 #define PARAMETER_SERVER_H_
00018 #include <string>
00019 #include <ros/ros.h>
00020 #include <boost/any.hpp>
00021
00022
00023
00024
00025 #include "pcl/point_cloud.h"
00026 #include "pcl/point_types.h"
00027 typedef pcl::PointXYZRGB point_type;
00028 typedef pcl::PointCloud<point_type> pointcloud_type;
00029
00030
00031 #define ROSCONSOLE_SEVERITY_INFO 1
00032
00038 class ParameterServer {
00039 public:
00043 static ParameterServer* instance();
00044
00052 template<typename T>
00053 void set(const std::string param, T value) {
00054 if(config.count(param)==0){
00055 ROS_ERROR("ParameterServer: Ignoring invalid parameter: \"%s\"", param.c_str());
00056 return;
00057 }
00058 try{
00059 boost::any_cast<T>(value);
00060 } catch (boost::bad_any_cast e) {
00061 ROS_ERROR("ParameterServer: Ignoring invalid parameter type: %s", e.what());
00062 return;
00063 }
00064 config[param] = value;
00065 }
00066
00067 template<typename T>
00068 T get(const std::string param) {
00069 if(config.count(param)==0){
00070 ROS_FATAL("ParameterServer object queried for invalid parameter \"%s\"", param.c_str());
00071 assert(config.count(param)==0);
00072 }
00073 boost::any value = config[param];
00074 return boost::any_cast<T>(value);
00075 }
00076
00080 std::string getDescription(std::string param_name);
00081
00085 std::map<std::string, boost::any>& getConfigData(){
00086 return config;
00087 }
00088
00094 void getValues();
00095 private:
00096 void addOption(std::string name, boost::any value, std::string description);
00097 std::map<std::string, boost::any> config;
00098 std::map<std::string, std::string> descriptions;
00099
00100 static ParameterServer* _instance;
00101 std::string pre;
00102 ros::NodeHandle handle;
00103
00108 ParameterServer();
00109
00113 void defaultConfig();
00114
00118 void checkValues();
00119
00129 template<typename T>
00130 T getFromParameterServer(const std::string param, T def) {
00131 std::string fullParam = param;
00132 T result;
00133 handle.param(fullParam, result, def);
00134 return result;
00135 }
00136 };
00137
00138 #endif