auto_config.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2014, Intermodalics BVBA
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Intermodalics BVBA nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H
36 #define RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H
37 
39 #include <boost/thread/shared_mutex.hpp>
40 
42 
47 {
48 public:
50 
51  std::string prefix_;
52  std::string name;
53  std::string type;
54  int parent;
55  int id;
56  bool state;
57 
58  AutoConfig();
59  AutoConfig(const RTT::PropertyBag &bag);
60  ~AutoConfig();
61 
62  bool __fromMessage__(dynamic_reconfigure::Config &msg, const AutoConfig &sample);
63  static bool __fromMessage__(AutoConfig &config, dynamic_reconfigure::Config &msg, const AutoConfig &sample);
64  void __toMessage__(dynamic_reconfigure::Config &msg) const;
65  static void __toMessage__(const AutoConfig &config, dynamic_reconfigure::Config &msg);
66 
67  void __toServer__(const ros::NodeHandle &nh) const;
68  void __fromServer__(const ros::NodeHandle &nh);
69  void __clamp__(const ServerType *server);
70  uint32_t __level__(const AutoConfig &config) const;
71 
72  static dynamic_reconfigure::ConfigDescriptionPtr __getDescriptionMessage__(const ServerType *server);
73  static const AutoConfig& __getDefault__(const ServerType *server);
74  static const AutoConfig& __getMax__(const ServerType *server);
75  static const AutoConfig& __getMin__(const ServerType *server);
76 
77  static void __refreshDescription__(const ServerType *server);
78 
79  bool updateProperties(RTT::PropertyBag &) const;
80  bool fromProperties(const RTT::PropertyBag &);
81 
82 private:
83  struct Cache;
85  static std::map<const ServerType *, CachePtr> cache_;
86  static boost::shared_mutex cache_mutex_;
87  static void buildCache(const ServerType *server, RTT::TaskContext *owner);
88 };
89 
91  dynamic_reconfigure::ConfigDescriptionPtr description_message_;
95 };
96 
97 } // namespace rtt_dynamic_reconfigure
98 
99 
100 #include "server.h"
101 
102 namespace rtt_dynamic_reconfigure {
103 
104 template <>
106  static bool propertiesFromConfig(AutoConfig &config, uint32_t, RTT::PropertyBag &bag) { return config.updateProperties(bag); }
107  static bool configFromProperties(AutoConfig &config, const RTT::PropertyBag &bag) { return config.fromProperties(bag); }
108 };
109 
110 template <>
113 
114  static void getMin(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getMin__(server); }
115  static void getMax(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getMax__(server); }
116  static void getDefault(AutoConfig &config, const ServerType *server) { config = AutoConfig::__getDefault__(server); }
117  static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *server) { return AutoConfig::__getDescriptionMessage__(server); }
118 
119  static const bool canRefresh = true;
120  static void refreshDescription(const ServerType *server) { AutoConfig::__refreshDescription__(server); }
121 
122  static void toMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__toMessage__(message); }
123  static void fromMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *server) { config.__fromMessage__(message, server->getConfig()); }
124  static void clamp(AutoConfig &config, const ServerType *server) { config.__clamp__(server); }
125 
128  }
129 };
130 
131 } // namespace rtt_dynamic_reconfigure
132 
133 #endif // RTT_DYNAMIC_RECONFIGURE_AUTO_CONFIG_H
bool __fromMessage__(dynamic_reconfigure::Config &msg, const AutoConfig &sample)
bool updateProperties(RTT::PropertyBag &) const
Server< AutoConfig > ServerType
Definition: auto_config.h:49
static void getMin(AutoConfig &config, const ServerType *server)
Definition: auto_config.h:114
static bool configFromProperties(AutoConfig &config, const RTT::PropertyBag &bag)
Definition: auto_config.h:107
static dynamic_reconfigure::ConfigDescriptionPtr __getDescriptionMessage__(const ServerType *server)
static RTT::internal::AssignableDataSource< RTT::PropertyBag >::shared_ptr getDataSource(AutoConfig &config, const ServerType *)
Definition: auto_config.h:126
static void getDefault(AutoConfig &config, const ServerType *server)
Definition: auto_config.h:116
void __fromServer__(const ros::NodeHandle &nh)
void __toMessage__(dynamic_reconfigure::Config &msg) const
dynamic_reconfigure::ConfigDescriptionPtr description_message_
Definition: auto_config.h:91
bool fromProperties(const RTT::PropertyBag &)
const ConfigType & getConfig() const
Definition: server.h:250
static void refreshDescription(const ServerType *server)
Definition: auto_config.h:120
boost::shared_ptr< Cache > CachePtr
Definition: auto_config.h:83
static void clamp(AutoConfig &config, const ServerType *server)
Definition: auto_config.h:124
uint32_t __level__(const AutoConfig &config) const
static void buildCache(const ServerType *server, RTT::TaskContext *owner)
static void toMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *)
Definition: auto_config.h:122
static const AutoConfig & __getDefault__(const ServerType *server)
static const AutoConfig & __getMin__(const ServerType *server)
boost::intrusive_ptr< AssignableDataSource< T > > shared_ptr
static void fromMessage(AutoConfig &config, dynamic_reconfigure::Config &message, const ServerType *server)
Definition: auto_config.h:123
static void __refreshDescription__(const ServerType *server)
void __clamp__(const ServerType *server)
static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *server)
Definition: auto_config.h:117
static void getMax(AutoConfig &config, const ServerType *server)
Definition: auto_config.h:115
static std::map< const ServerType *, CachePtr > cache_
Definition: auto_config.h:85
static bool propertiesFromConfig(AutoConfig &config, uint32_t, RTT::PropertyBag &bag)
Definition: auto_config.h:106
static const AutoConfig & __getMax__(const ServerType *server)
void __toServer__(const ros::NodeHandle &nh) const
static boost::shared_mutex cache_mutex_
Definition: auto_config.h:86


rtt_dynamic_reconfigure
Author(s): Johannes Meyer
autogenerated on Sat Jun 8 2019 18:05:06