Project

General

Profile

Statistics
| Branch: | Revision:

root / rgbdslam / src / parameter_server.h @ 9240aaa3

History | View | Annotate | Download (2.83 KB)

1 9240aaa3 Alex
/* This file is part of RGBDSLAM.
2
 * 
3
 * RGBDSLAM is free software: you can redistribute it and/or modify
4
 * it under the terms of the GNU General Public License as published by
5
 * the Free Software Foundation, either version 3 of the License, or
6
 * (at your option) any later version.
7
 * 
8
 * RGBDSLAM is distributed in the hope that it will be useful,
9
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
10
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
11
 * GNU General Public License for more details.
12
 * 
13
 * You should have received a copy of the GNU General Public License
14
 * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
15
 */
16
#ifndef PARAMETER_SERVER_H_
17
#define PARAMETER_SERVER_H_
18
#include <string>
19
#include <ros/ros.h>
20
#include <boost/any.hpp>
21
22
//this is a global definition of the points to be used
23
//changes to omit color would need adaptations in 
24
//the visualization too
25
#include "pcl/point_cloud.h"
26
#include "pcl/point_types.h"
27
typedef pcl::PointXYZRGB point_type;
28
typedef pcl::PointCloud<point_type> pointcloud_type;
29
#define CONCURRENT_EDGE_COMPUTATION
30
31
/*!
32
 * \brief Getting values from parameter server
33
 * This class is used for getting the parameters from
34
 * the parameter server
35
 */
36
class ParameterServer {
37
public:
38
    /*!
39
     * Returns the singleton instance
40
     */
41
    static ParameterServer* instance();
42
43
    /*!
44
     * The method returns a value from the local cache.
45
     * You can use bool, int, double and std::string for T
46
     *
47
     * \param param the name of the parameter
48
     * \return the parameter value
49
     */
50
    template<typename T>
51
    T get(const std::string param) {
52
        ROS_ERROR_COND(config.count(param)==0, "ParameterServer object queried for invalid parameter \"%s\"", param.c_str());
53
        boost::any value = config[param];
54
        return boost::any_cast<T>(value);
55
    }
56
57
private:
58
    std::map<std::string, boost::any> config;
59
60
    static ParameterServer* _instance;
61
    std::string pre;
62
    ros::NodeHandle handle;
63
64
    /*!
65
     * Default constructor
66
     * private, because of singleton
67
     */
68
    ParameterServer();
69
70
    /*!
71
     * Receives all values from the parameter server and store them
72
     * in the map 'config'.
73
     * Will be called in the constructor
74
     */
75
    void getValues();
76
77
    /*!
78
     * Loads the default configuration
79
     */
80
    void defaultConfig();
81
82
    /*!
83
     * Returns a value from the parameter server
84
     * Will only be used by getValue()
85
     *
86
     * \param param name of the parameter
87
     * \param def default value (get through defaultConfig())
88
     *
89
     * \return the parameter value
90
     */
91
    template<typename T>
92
    T getFromParameterServer(const std::string param, T def) {
93
        std::string fullParam = param;
94
        T result;
95
        handle.param(fullParam, result, def);
96
        return result;
97
    }
98
};
99
100
#endif /* PARAMETER_SERVER_H_ */