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 #ifdef HEMACLOUDS
00023 #define PCL_NO_PRECOMPILE
00024 #endif
00025
00026
00027
00028
00029
00030 #include "pcl_ros/point_cloud.h"
00031 #include "pcl/point_types.h"
00032 #include "point_types.h"
00033 #ifdef RGB_IS_4TH_DIM
00034 typedef pcl::PointXYZ point_type;
00035 typedef pcl::PointXYZNormal point_normal_type;
00036 #elif defined(HEMACLOUDS)
00037 typedef hema::PointXYZRGBCamSL point_type;
00038 #else
00039 typedef pcl::PointXYZRGB point_type;
00040 typedef pcl::PointXYZRGBNormal point_normal_type;
00041 #endif
00042 typedef pcl::PointCloud<point_type> pointcloud_type;
00043 typedef pcl::PointCloud<point_normal_type> pointcloud_normal_type;
00044
00045
00046 #define ROSCONSOLE_SEVERITY_INFO 1
00047
00053 class ParameterServer {
00054 public:
00058 static ParameterServer* instance();
00059
00067 template<typename T>
00068 void set(const std::string param, T value) {
00069 #ifdef RGBDSLAM_DEBUG
00070 if(config.count(param)==0){
00071 ROS_ERROR("ParameterServer: Ignoring invalid parameter: \"%s\"", param.c_str());
00072 return;
00073 }
00074 #endif
00075 config[param] = value;
00076 setOnParameterServer(pre+param, value);
00077 }
00078
00086 template<typename T>
00087 T get(const std::string param) {
00088 #ifdef RGBDSLAM_DEBUG
00089 if(config.count(param)==0){
00090 ROS_FATAL("ParameterServer object queried for invalid parameter \"%s\"", param.c_str());
00091 assert(config.count(param)==0);
00092 }
00093 #endif
00094 boost::any value = config[param];
00095 try{
00096 return boost::any_cast<T>(value);
00097 } catch( boost::bad_any_cast bac){
00098 std::cerr << "Bad cast: Requested data type <" << typeid(T).name() << "> for parameter '" << param << "'";
00099 throw;
00100 }
00101 }
00102
00106 std::string getDescription(std::string param_name);
00107
00111 std::map<std::string, boost::any>& getConfigData(){
00112 return config;
00113 }
00114
00120 void getValues();
00121 private:
00122 void addOption(std::string name, boost::any value, std::string description);
00123 std::map<std::string, boost::any> config;
00124 std::map<std::string, std::string> descriptions;
00125
00126 static ParameterServer* _instance;
00127 std::string pre;
00128 ros::NodeHandle handle;
00129
00134 ParameterServer();
00135
00139 void defaultConfig();
00140
00144 void checkValues();
00145
00155 template<typename T>
00156 T getFromParameterServer(const std::string param, T def) {
00157 T result;
00158 handle.param(param, result, def);
00159 return result;
00160 }
00161
00162 template<typename T>
00163 void setOnParameterServer(const std::string param, T new_val) {
00164 handle.setParam(param, new_val);
00165 }
00166 };
00167
00168 #endif