$search
00001 //TODO: deprecated, can probably be deleted 00002 00003 #pragma once 00004 00005 #include <dynamic_reconfigure/server.h> 00006 00007 template <class T> 00008 class Reconfigurable_Node { 00009 protected: 00010 ros::ServiceServer set_service_; 00011 Reconfigurable_Node(const std::string& ns) : _n(ros::NodeHandle(getCorrectedNS(ns))), srv(_n), first_(true) 00012 { 00013 update_pub_ = _n.advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true); 00014 } 00015 00016 void setReconfigureCallback(const boost::function<void(T &, uint32_t level)> &callback) { 00017 srv.setCallback(callback); 00018 } 00019 00020 void setReconfigureCallback2(const boost::function<void(T &, uint32_t level)> &callback_s, const boost::function<void(T &)> &callback_get) { 00021 callback_set_=callback_s; 00022 callback_get_=callback_get; 00023 srv.setCallback(boost::bind(&callback_set, this, _1, _2)); 00024 //srv.setCallback(callback_s); 00025 } 00026 00027 void updateConfig(const T &config_) 00028 { 00029 config_.__toServer__(_n); 00030 dynamic_reconfigure::Config msg; 00031 config_.__toMessage__(msg); 00032 update_pub_.publish(msg); 00033 } 00034 00035 // callback for dynamic reconfigure 00036 static void callback_set(Reconfigurable_Node<T> *inst, T &config, uint32_t level) 00037 { 00038 if(!inst->first_) 00039 inst->callback_set_(config, level); 00040 else { 00041 inst->callback_get_(config); 00042 inst->updateConfig(config); 00043 } 00044 inst->first_=false; 00045 } 00046 00047 private: 00048 ros::NodeHandle _n; 00049 dynamic_reconfigure::Server<T> srv; 00050 ros::Publisher update_pub_; 00051 bool first_; 00052 boost::function<void(T &, uint32_t level)> callback_set_; 00053 boost::function<void(T &)> callback_get_; 00054 00055 std::string getCorrectedNS(const std::string &s) { 00056 static int num=0; 00057 00058 std::ostringstream oss; 00059 oss << "~/" << s << num; 00060 ++num; 00061 00062 return oss.str(); 00063 } 00064 00065 };