parameter_server.h
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
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 //this is a global definition of the points to be used
00023 //changes to omit color would need adaptations in 
00024 //the visualization too
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 //#define CONCURRENT_EDGE_COMPUTATION
00030 //Compile out DEBUG Statements. Hardly benefitial though
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); //fails if wrong param type
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 /* PARAMETER_SERVER_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


rgbdslam
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Wed Dec 26 2012 15:53:09