Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H
00036 #define RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H
00037
00038 #include <rtt_dynamic_reconfigure/server.h>
00039 #include <boost/thread/shared_mutex.hpp>
00040
00041 namespace rtt_dynamic_reconfigure {
00042
00046 class AutoConfig : public RTT::PropertyBag
00047 {
00048 public:
00049 typedef Server<AutoConfig> ServerType;
00050
00051 std::string prefix_;
00052 std::string name;
00053 std::string type;
00054 int parent;
00055 int id;
00056 bool state;
00057
00058 AutoConfig();
00059 AutoConfig(const RTT::PropertyBag &bag);
00060 ~AutoConfig();
00061
00062 bool __fromMessage__(dynamic_reconfigure::Config &msg, const AutoConfig &sample);
00063 static bool __fromMessage__(AutoConfig &config, dynamic_reconfigure::Config &msg, const AutoConfig &sample);
00064 void __toMessage__(dynamic_reconfigure::Config &msg) const;
00065 static void __toMessage__(const AutoConfig &config, dynamic_reconfigure::Config &msg);
00066
00067 void __toServer__(const ros::NodeHandle &nh) const;
00068 void __fromServer__(const ros::NodeHandle &nh);
00069 void __clamp__(const ServerType *server);
00070 uint32_t __level__(const AutoConfig &config) const;
00071
00072 static dynamic_reconfigure::ConfigDescriptionPtr __getDescriptionMessage__(const ServerType *server);
00073 static const AutoConfig& __getDefault__(const ServerType *server);
00074 static const AutoConfig& __getMax__(const ServerType *server);
00075 static const AutoConfig& __getMin__(const ServerType *server);
00076
00077 static void __refreshDescription__(const ServerType *server);
00078
00079 bool updateProperties(RTT::PropertyBag &) const;
00080 bool fromProperties(const RTT::PropertyBag &);
00081
00082 private:
00083 struct Cache;
00084 typedef boost::shared_ptr<Cache> CachePtr;
00085 static std::map<const ServerType *, CachePtr> cache_;
00086 static boost::shared_mutex cache_mutex_;
00087 static void buildCache(const ServerType *server, RTT::TaskContext *owner);
00088 };
00089
00090 struct AutoConfig::Cache {
00091 dynamic_reconfigure::ConfigDescriptionPtr description_message_;
00092 AutoConfig default_;
00093 AutoConfig max_;
00094 AutoConfig min_;
00095 };
00096
00097 }
00098
00099
00100 #include "server.h"
00101
00102 namespace rtt_dynamic_reconfigure {
00103
00104 template <>
00105 struct Updater<AutoConfig> {
00106 static bool propertiesFromConfig(AutoConfig &config, uint32_t, RTT::PropertyBag &bag) { return config.updateProperties(bag); }
00107 static bool configFromProperties(AutoConfig &config, const RTT::PropertyBag &bag) { return config.fromProperties(bag); }
00108 };
00109
00110 template <>
00111 struct dynamic_reconfigure_traits<AutoConfig> {
00112 typedef Server<AutoConfig> ServerType;
00113
00114 static void getMin(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getMin__(server); }
00115 static void getMax(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getMax__(server); }
00116 static void getDefault(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getDefault__(server); }
00117 static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *server) { return AutoConfig::__getDescriptionMessage__(server); }
00118
00119 static const bool canRefresh = true;
00120 static void refreshDescription(const ServerType *server) { AutoConfig::__refreshDescription__(server); }
00121
00122 static void toMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__toMessage__(message); }
00123 static void fromMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *server) { config.__fromMessage__(message, server->getConfig()); }
00124 static void clamp(AutoConfig &config, const ServerType *server) { config.__clamp__(server); }
00125
00126 static RTT::internal::AssignableDataSource<RTT::PropertyBag>::shared_ptr getDataSource(AutoConfig &config, const ServerType *) {
00127 return RTT::internal::AssignableDataSource<RTT::PropertyBag>::shared_ptr(new RTT::internal::ReferenceDataSource<RTT::PropertyBag>(config));
00128 }
00129 };
00130
00131 }
00132
00133 #endif // RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H