ddynamic_reconfigure.h
Go to the documentation of this file.
1 //
2 // Created by Noam Dori on 18/06/18.
3 //
4 //include space, written in C++03
5 #include <ros/ros.h>
6 #include <dynamic_reconfigure/server.h>
7 
8 #include <string>
9 #include <vector>
10 #include <map>
11 
12 #include <boost/shared_ptr.hpp>
13 #include <boost/function.hpp>
14 #include <boost/bind.hpp>
15 
16 #include "dd_param.h"
17 using namespace std;
18 using namespace boost;
19 using namespace dynamic_reconfigure;
20 
21 #ifndef DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H
22 #define DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H
23 namespace ddynamic_reconfigure {
24  // this is a map from the DDParam name to the object. Acts like a set with a search function.
25  typedef map<string,DDPtr> DDMap;
26  // the function you will use a lot
27  typedef boost::function<void(const DDMap&,int)> DDFunc;
28 
46  public:
52 
57  virtual void add(DDPtr param);
58 
66  virtual void add(DDParam *param);
67 
72  virtual void remove(DDPtr param);
73 
78  virtual void remove(DDParam *param);
79 
84  virtual void remove(string param_name);
85 
90  void setCallback(DDFunc callback);
91 
95  void clearCallback();
96 
100  virtual void start();
101 
106  void start(DDFunc callback);
107 
112  void start(void(*callback)(const DDMap&, int));
113 
120  template<class T>
121  void start(void(T::*callback)(const DDMap&, int), T *obj) {
122  DDFunc f = bind(callback,obj,_1,_2);
123  start();
124  }
125 
131  Value get(const char* name);
132 
138  DDPtr at(const char* name);
139 
146  friend ostream& operator<<(ostream& os, const DDynamicReconfigure &dd);
147  protected:
148 
153  ConfigDescription makeDescription();
154 
159  Config makeConfig();
160 
169  static bool internalCallback(DDynamicReconfigure *obj, Reconfigure::Request &req, Reconfigure::Response &rsp);
170 
178  DDMap params_;
185 
186  private:
187 
198  template <class T>
199  static int reassign(DDMap& map, const string &name, T value);
200 
207  int getUpdates(const Reconfigure::Request &req, DDMap &config);
208 
213  #ifdef __clang__
214  #pragma clang diagnostic push // CLion suppressor
215  #pragma ide diagnostic ignored "OCUnusedGlobalDeclarationInspection"
216  #endif
217 
222  #ifdef __clang__
223  #pragma clang diagnostic pop
224  #endif
225  };
226 
233  DDPtr at(const DDMap& map, const char* name); // I could do this with an operator, but its bad design.
234 
241  Value get(const DDMap& map, const char* name); // I could do this with an operator, but its bad design.
242 }
243 #endif //DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H
bool param(const std::string &param_name, T &param_val, const T &default_val)
ROSCPP_DECL void start()
boost::function< void(const DDMap &, int)> DDFunc
f
void start(void(T::*callback)(const DDMap &, int), T *obj)
starts the server, using the given callback in class-wise static method form.
void callback(const DDMap &map, int)
Definition: dd_server.cpp:26
map< string, DDPtr > DDMap
The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic pro...
DDMap params_
a map of all contained parameters.
DDPtr at(const DDMap &map, const char *name)
a tool people who use this API can use to find the param given within the param map.
The DDParam class is the abstraction of all parameter types, and is the template for creating them...
Definition: dd_param.h:48
ros::NodeHandle nh_
the ROS node handler to use to make everything ROS related.
ros::ServiceServer set_service_
the service server used to trigger parameter updates. It also contains the new parameters sent from c...
The Value class is used to wrap all basic data-types (bool,int,double,string) in something generic...
Definition: dd_value.h:29
ostream & operator<<(ostream &os, const DDParam &param)
Definition: dd_param.cpp:8
boost::shared_ptr< DDFunc > callback_
the use defined callback to call when parameters are updated.


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Thu May 16 2019 02:46:37