ddynamic_reconfigure.h
Go to the documentation of this file.
00001 //
00002 // Created by Noam Dori on 18/06/18.
00003 //
00004 //include space, written in C++03
00005 #include <ros/ros.h>
00006 #include <dynamic_reconfigure/server.h>
00007 
00008 #include <string>
00009 #include <vector>
00010 #include <map>
00011 
00012 #include <boost/shared_ptr.hpp>
00013 #include <boost/function.hpp>
00014 #include <boost/bind.hpp>
00015 
00016 #include "dd_param.h"
00017 using namespace std;
00018 using namespace boost;
00019 using namespace dynamic_reconfigure;
00020 
00021 #ifndef DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H
00022 #define DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H
00023 namespace ddynamic_reconfigure {
00024     // this is a map from the DDParam name to the object. Acts like a set with a search function.
00025     typedef map<string,DDPtr> DDMap;
00026     // the function you will use a lot
00027     typedef boost::function<void(const DDMap&,int)> DDFunc;
00028 
00045     class DDynamicReconfigure {
00046     public:
00051          explicit DDynamicReconfigure(ros::NodeHandle &nh);
00052 
00057          virtual void add(DDPtr param);
00058 
00066          virtual void add(DDParam *param);
00067 
00072          virtual void remove(DDPtr param);
00073 
00078          virtual void remove(DDParam *param);
00079 
00084          virtual void remove(string param_name);
00085 
00090          void setCallback(DDFunc callback);
00091 
00095          void clearCallback();
00096 
00100          virtual void start();
00101 
00106          void start(DDFunc callback);
00107 
00112          void start(void(*callback)(const DDMap&, int));
00113 
00120          template<class T>
00121          void start(void(T::*callback)(const DDMap&, int), T *obj) {
00122             DDFunc f = bind(callback,obj,_1,_2);
00123             start();
00124          }
00125 
00131         Value get(const char* name);
00132 
00138         DDPtr at(const char* name);
00139 
00146         friend ostream& operator<<(ostream& os, const DDynamicReconfigure &dd);
00147     protected:
00148 
00153          ConfigDescription makeDescription();
00154 
00159          Config makeConfig();
00160 
00169         static bool internalCallback(DDynamicReconfigure *obj, Reconfigure::Request &req, Reconfigure::Response &rsp);
00170 
00174          ros::NodeHandle nh_;
00178          DDMap params_;
00184          ros::Publisher desc_pub_, update_pub_;
00185 
00186     private:
00187 
00198          template <class T>
00199          static int reassign(DDMap& map, const string &name, T value);
00200 
00207          int getUpdates(const Reconfigure::Request &req, DDMap &config);
00208 
00212           boost::shared_ptr<DDFunc> callback_;
00213           #ifdef __clang__
00214           #pragma clang diagnostic push // CLion suppressor
00215           #pragma ide diagnostic ignored "OCUnusedGlobalDeclarationInspection"
00216           #endif
00217 
00221           ros::ServiceServer set_service_;
00222           #ifdef __clang__
00223           #pragma clang diagnostic pop
00224           #endif
00225     };
00226 
00233      DDPtr at(const DDMap& map, const char* name); // I could do this with an operator, but its bad design.
00234 
00241      Value get(const DDMap& map, const char* name); // I could do this with an operator, but its bad design.
00242 }
00243 #endif //DDYNAMIC_RECONFIGURE_DDYNAMIC_RECONFIGURE_H


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Wed May 15 2019 04:39:27