Codebase list ros-dynamic-reconfigure / upstream/1.5.48
New upstream version 1.5.48 Jochen Sprickerhof 6 years ago
13 changed file(s) with 601 addition(s) and 22 deletion(s). Raw diff Collapse all Expand all
00 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
11 Changelog for package dynamic_reconfigure
22 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
3
4 1.5.48 (2017-04-07)
5 -------------------
6 * [Bugfix] dont enforce ROS names for constants (`#84 <https://github.com/ros/dynamic_reconfigure/issues/84>`_)
7 * [Compiler warnings] avoid unused-parameter compiler warnings in specialized ParamDescription<std::string>::clamp() (`#83 <https://github.com/ros/dynamic_reconfigure/issues/83>`_)
8 * Contributors: Johannes Meyer, Mikael Arguedas
9
10 1.5.47 (2017-03-27)
11 -------------------
12 * reset received_configuration\_ for every request sent (`#82 <https://github.com/ros/dynamic_reconfigure/issues/82>`_)
13 * Rename arguments (with a\_ prefix) to avoid Wshadow warnings. (`#80 <https://github.com/ros/dynamic_reconfigure/issues/80>`_)
14 handle infinity in python generation, fixes (`#77 <https://github.com/ros/dynamic_reconfigure/issues/77>`_)
15 * Add a c++ Dynamic Reconfigure Client (`#78 <https://github.com/ros/dynamic_reconfigure/issues/78>`_)
16 * Enforce valid descriptions in cfg files (`#74 <https://github.com/ros/dynamic_reconfigure/issues/74>`_)
17 * Fix callback returned by get_description_callback (`#73 <https://github.com/ros/dynamic_reconfigure/issues/73>`_) from ros/description_cb
18 * Contributors: Jeff Eberl, Mikael Arguedas
319
420 1.5.46 (2016-11-15)
521 -------------------
11 project(dynamic_reconfigure)
22
33 find_package(catkin REQUIRED COMPONENTS message_generation roscpp std_msgs)
4 find_package(Boost REQUIRED COMPONENTS system thread)
4 find_package(Boost REQUIRED COMPONENTS system thread chrono)
55
66 include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
77
99
1010 add_message_files(
1111 DIRECTORY msg
12 FILES
12 FILES
1313 BoolParameter.msg Config.msg Group.msg IntParameter.msg SensorLevels.msg
1414 ConfigDescription.msg DoubleParameter.msg GroupState.msg ParamDescription.msg StrParameter.msg)
1515
4040 install(DIRECTORY include/dynamic_reconfigure/
4141 DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
4242 FILES_MATCHING PATTERN "*.h")
43
43
4444 install(TARGETS dynamic_reconfigure_config_init_mutex
4545 ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
4646 LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
4848
4949 gen.add("int_enum_", int_t, 1, "Int enum",0, 0, 3, edit_method = enum)
5050 gen.add("int_", int_t, 1, "Int parameter",0, -10, 10)
51 gen.add("double_", double_t, 2, "double parameter",0, -2, 10)
51 gen.add("double_", double_t, 2, "double parameter", 0, -2, 10)
52 gen.add("double_no_minmax", double_t, 2, "double parameter without boundaries", 1)
53 gen.add("double_no_max", double_t, 2, "double parameter without max value", 2, 0)
5254 gen.add("str_", str_t, 4, "String parameter","foo")
5355 gen.add("mstr_", str_t, 4, "Multibyte String parameter","bar")
5456 gen.add("bool_", bool_t, 8, "Boolean parameter",False)
6668 group3 = group2.add_group("Group3")
6769 group3.add("deep_var_int", int_t, 0, "Were very far down now", 0, 0, 3, edit_method = enum)
6870 group3.add("deep_var_bool", bool_t, 0, "Were even farther down now!!", True)
71 group3.add("deep_var_double", double_t, 0, "Were super far down now!!", -1.0)
6972
7073 group12 = gen.add_group("Upper Group 2")
7174 group12.add("some_param", int_t, 0, "Some param", 20)
0 /*********************************************************************
1 * Software License Agreement (BSD License)
2 *
3 * Copyright (c) 2015-2016, Myrmex, Inc.
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions
8 * are met:
9 *
10 * * Redistributions of source code must retain the above copyright
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 * * Neither the name of the Myrmex, Inc nor the names of its
17 * contributors may be used to endorse or promote products derived
18 * from this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
32 *********************************************************************/
33
34 /**
35
36 Author: Aris Synodinos
37
38 Handles sychronizing node state with the configuration server and setting/getting
39 configuration.
40
41 */
42
43 #ifndef __CLIENT_H__
44 #define __CLIENT_H__
45
46 #include <boost/chrono.hpp>
47 #include <boost/function.hpp>
48 #include <boost/thread.hpp>
49 #include <ros/node_handle.h>
50 #include <dynamic_reconfigure/ConfigDescription.h>
51 #include <dynamic_reconfigure/Reconfigure.h>
52
53 namespace dynamic_reconfigure {
54
55 template <class ConfigType>
56 class Client {
57 public:
58 /**
59 * @brief Client Constructs a statefull dynamic_reconfigure client
60 * @param name The full path of the dynamic_reconfigure::Server
61 * @param config_callback A callback that should be called when the server
62 * informs the clients of a successful reconfiguration
63 * @param description_callback A callback that should be called when the
64 * server infrorms the clients of the description of the reconfiguration
65 * parameters and groups
66 */
67 Client(
68 const std::string& name,
69 const boost::function<void(const ConfigType&)> config_callback = 0,
70 const boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
71 description_callback = 0)
72 : name_(name),
73 nh_(name),
74 received_configuration_(false),
75 received_description_(false),
76 config_callback_(config_callback),
77 description_callback_(description_callback) {
78 set_service_ =
79 nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");
80
81 config_sub_ =
82 nh_.subscribe("parameter_updates", 1,
83 &Client<ConfigType>::configurationCallback, this);
84
85 descr_sub_ = nh_.subscribe("parameter_descriptions", 1,
86 &Client<ConfigType>::descriptionCallback, this);
87 }
88 /**
89 * @brief Client Constructs a statefull dynamic_reconfigure client
90 * @param name The full path of the dynamic_reconfigure::Server
91 * @param nh The nodehandle to the full path of the Server (for nodelets)
92 * @param config_callback A callback that should be called when the server
93 * informs the clients of a successful reconfiguration
94 * @param description_callback A callback that should be called when the
95 * server infrorms the clients of the description of the reconfiguration
96 * parameters and groups
97 */
98 Client(
99 const std::string& name, const ros::NodeHandle& nh,
100 const boost::function<void(const ConfigType&)> config_callback = 0,
101 const boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
102 description_callback = 0)
103 : name_(name),
104 nh_(nh),
105 received_configuration_(false),
106 received_description_(false),
107 config_callback_(config_callback),
108 description_callback_(description_callback) {
109 set_service_ =
110 nh_.serviceClient<dynamic_reconfigure::Reconfigure>("set_parameters");
111
112 config_sub_ =
113 nh_.subscribe("parameter_updates", 1,
114 &Client<ConfigType>::configurationCallback, this);
115
116 descr_sub_ = nh_.subscribe("parameter_descriptions", 1,
117 &Client<ConfigType>::descriptionCallback, this);
118 }
119 /**
120 * @brief setConfigurationCallback Sets the user defined configuration
121 * callback function
122 * @param config_callback A function pointer
123 */
124 void setConfigurationCallback(
125 const boost::function<void(const ConfigType&)>& config_callback) {
126 config_callback_ = config_callback;
127 }
128 /**
129 * @brief setDescriptionCallback Sets the user defined description callback
130 * function
131 * @param description_callback A function pointer
132 */
133 void setDescriptionCallback(const boost::function<void(
134 const dynamic_reconfigure::ConfigDescription&)>& description_callback) {
135 description_callback_ = description_callback;
136 }
137 /**
138 * @brief setConfiguration Attempts to set the configuration to the server
139 * @param configuration The requested configuration
140 * @return True if the server accepted the request (not the reconfiguration)
141 */
142 bool setConfiguration(const ConfigType& configuration) {
143 ConfigType temp = configuration;
144 return setConfiguration(temp);
145 }
146 /**
147 * @brief setConfiguration Attempts to set the configuration to the server
148 * @param configuration The requested configuration, gets overwritten with the
149 * reply from the reconfigure server
150 * @return True if the server accepted the request (not the reconfiguration)
151 */
152 bool setConfiguration(ConfigType& configuration) {
153 dynamic_reconfigure::Reconfigure srv;
154 received_configuration_ = false;
155 configuration.__toMessage__(srv.request.config);
156 if (set_service_.call(srv)) {
157 configuration.__fromMessage__(srv.response.config);
158 return true;
159 } else {
160 ROS_WARN("Could not set configuration");
161 return false;
162 }
163 }
164 /**
165 * @brief getCurrentConfiguration Gets the latest configuration from the
166 * dynamic_reconfigure::Server
167 * @param configuration The object where the configuration will be stored
168 * @param timeout The duration that the client should wait for the
169 * configuration, if set to ros::Duration(0) will wait indefinetely
170 * @return False if the timeout has happened
171 */
172 bool getCurrentConfiguration(
173 ConfigType& configuration,
174 const ros::Duration& timeout = ros::Duration(0)) {
175 if (timeout == ros::Duration(0)) {
176 ROS_INFO_ONCE("Waiting for configuration...");
177 boost::mutex::scoped_lock lock(mutex_);
178 while (!received_configuration_) {
179 if (!ros::ok()) return false;
180 cv_.wait(lock);
181 }
182 } else {
183 ros::Time start_time = ros::Time::now();
184 boost::mutex::scoped_lock lock(mutex_);
185 while (!received_configuration_) {
186 if (!ros::ok()) return false;
187 ros::Duration time_left = timeout - (ros::Time::now() - start_time);
188 if (time_left.toSec() <= 0.0) return false;
189 cv_.wait_for(lock, boost::chrono::nanoseconds(time_left.toNSec()));
190 }
191 }
192 configuration = latest_configuration_;
193 return true;
194 }
195 /**
196 * @brief getDefaultConfiguration Gets the latest default configuration from
197 * the dynamic_reconfigure::Server
198 * @param configuration The object where the configuration will be stored
199 * @param timeout The duration that the client should wait for the
200 * configuration, if set to ros::Duration(0) will wait indefinetely
201 * @return False if the timeout has happened
202 */
203 bool getDefaultConfiguration(
204 ConfigType& configuration,
205 const ros::Duration& timeout = ros::Duration(0)) {
206 ConfigDescription answer;
207 if (getDescription(answer, timeout)) {
208 configuration.__fromMessage__(answer.dflt);
209 return true;
210 } else {
211 return false;
212 }
213 }
214 /**
215 * @brief getMinConfiguration Gets the latest minimum configuration from
216 * the dynamic_reconfigure::Server
217 * @param configuration The object where the configuration will be stored
218 * @param timeout The duration that the client should wait for the
219 * configuration, if set to ros::Duration(0) will wait indefinetely
220 * @return False if the timeout has happened
221 */
222 bool getMinConfiguration(ConfigType& configuration,
223 const ros::Duration& timeout = ros::Duration(0)) {
224 ConfigDescription answer;
225 if (getDescription(answer, timeout)) {
226 configuration.__fromMessage__(answer.min);
227 return true;
228 } else {
229 return false;
230 }
231 }
232 /**
233 * @brief getMaxConfiguration Gets the latest maximum configuration from
234 * the dynamic_reconfigure::Server
235 * @param configuration The object where the configuration will be stored
236 * @param timeout The duration that the client should wait for the
237 * configuration, if set to ros::Duration(0) will wait indefinetely
238 * @return False if the timeout has happened
239 */
240 bool getMaxConfiguration(ConfigType& configuration,
241 const ros::Duration& timeout = ros::Duration(0)) {
242 ConfigDescription answer;
243 if (getDescription(answer, timeout)) {
244 configuration.__fromMessage__(answer.max);
245 return true;
246 } else {
247 return false;
248 }
249 }
250 /**
251 * @brief getName Gets the name of the Dynamic Reconfigure Client
252 * @return Copy of the member variable
253 */
254 std::string getName() const { return name_; }
255
256 private:
257 void configurationCallback(const dynamic_reconfigure::Config& configuration) {
258 boost::mutex::scoped_lock lock(mutex_);
259 dynamic_reconfigure::Config temp_config = configuration;
260 received_configuration_ = true;
261 latest_configuration_.__fromMessage__(temp_config);
262 cv_.notify_all();
263
264 if (config_callback_) {
265 try {
266 config_callback_(latest_configuration_);
267 } catch (std::exception& e) {
268 ROS_WARN("Configuration callback failed with exception %s", e.what());
269 } catch (...) {
270 ROS_WARN("Configuration callback failed with unprintable exception");
271 }
272 } else {
273 ROS_DEBUG(
274 "Unable to call Configuration callback because none was set.\n" \
275 "See setConfigurationCallback");
276 }
277 }
278
279 void descriptionCallback(
280 const dynamic_reconfigure::ConfigDescription& description) {
281 boost::mutex::scoped_lock lock(mutex_);
282 received_description_ = true;
283 latest_description_ = description;
284 cv_.notify_all();
285
286 if (description_callback_) {
287 try {
288 description_callback_(description);
289 } catch (std::exception& e) {
290 ROS_WARN("Description callback failed with exception %s", e.what());
291 } catch (...) {
292 ROS_WARN("Description callback failed with unprintable exception");
293 }
294 } else {
295 ROS_DEBUG(
296 "Unable to call Description callback because none was set.\n" \
297 "See setDescriptionCallback");
298 }
299 }
300
301 bool getDescription(ConfigDescription& configuration,
302 const ros::Duration& timeout) {
303 if (timeout == ros::Duration(0)) {
304 ROS_INFO_ONCE("Waiting for configuration...");
305 boost::mutex::scoped_lock lock(mutex_);
306 while (!received_description_) {
307 if (!ros::ok()) return false;
308 cv_.wait(lock);
309 }
310 } else {
311 ros::Time start_time = ros::Time::now();
312 boost::mutex::scoped_lock lock(mutex_);
313 while (!received_description_) {
314 if (!ros::ok()) return false;
315 ros::Duration time_left = timeout - (ros::Time::now() - start_time);
316 if (time_left.toSec() <= 0.0) return false;
317 cv_.wait_for(lock, boost::chrono::nanoseconds(time_left.toNSec()));
318 }
319 }
320 configuration = latest_description_;
321 return true;
322 }
323
324 std::string name_;
325 bool received_configuration_;
326 ConfigType latest_configuration_;
327 bool received_description_;
328 dynamic_reconfigure::ConfigDescription latest_description_;
329 boost::condition_variable cv_;
330 boost::mutex mutex_;
331 ros::NodeHandle nh_;
332 ros::ServiceClient set_service_;
333 ros::Subscriber descr_sub_;
334 ros::Subscriber config_sub_;
335
336 boost::function<void(const ConfigType&)> config_callback_;
337 boost::function<void(const dynamic_reconfigure::ConfigDescription&)>
338 description_callback_;
339 };
340 }
341
342 #endif // __CLIENT_H__
00 <package>
11 <name>dynamic_reconfigure</name>
2 <version>1.5.46</version>
2 <version>1.5.48</version>
33 <description>
44 This unary stack contains the dynamic_reconfigure package which provides a means to change
55 node parameters at any time without having to restart the node.
277277 """
278278 Get the current description_callback
279279 """
280 return self._config_callback
280 return self._description_callback
281281
282282 def set_description_callback(self, value):
283283 """
5858 double_t = "double"
5959
6060 id = 0
61
62
63 def check_description(description):
64 quotes = ['"', "'"]
65 for quote in quotes:
66 if description.find(quote) != -1:
67 raise Exception(r"""quotes not allowed in description string `%s`""" % description)
68
69
70 def check_name(name):
71 pattern = r'^[a-zA-Z][a-zA-Z0-9_]*$'
72 if not re.match(pattern, name):
73 raise Exception("The name of field \'%s\' does not follow the ROS naming conventions, see http://wiki.ros.org/ROS/Patterns/Conventions"%name)
74
6175
6276 class ParameterGenerator:
6377 minval = {
123137 }
124138 if type == str_t and (max != None or min != None):
125139 raise Exception("Max or min specified for %s, which is of string type"%name)
126 pattern = r'^[a-zA-Z][a-zA-Z0-9_]*$'
127 if not re.match(pattern, name):
128 raise Exception("The name of field \'%s\' does not follow the ROS naming conventions, see http://wiki.ros.org/ROS/Patterns/Conventions"%name)
129
140
141 check_name(name)
142 check_description(description)
130143 self.gen.fill_type(newparam)
131144 self.gen.check_type_fill_default(newparam, 'default', self.gen.defval[paramtype])
132145 self.gen.check_type_fill_default(newparam, 'max', self.gen.maxval[paramtype])
204217 def pytype(self, drtype):
205218 return { 'str':str, 'int':int, 'double':float, 'bool':bool }[drtype]
206219
207
208220 def check_type(self, param, field):
209221 drtype = param['type']
210222 name = param['name']
243255 'srcfile' : inspect.getsourcefile(inspect.currentframe().f_back.f_code),
244256 'description' : descr
245257 }
258 check_description(descr)
246259 self.fill_type(newconst)
247260 self.check_type(newconst, 'value')
248261 self.constants.append(newconst)
251264 def enum(self, constants, description):
252265 if len(set(const['type'] for const in constants)) != 1:
253266 raise Exception("Inconsistent types in enum!")
267 check_description(description)
254268 return repr({ 'enum' : constants, 'enum_description' : description })
255269
256270 # Wrap add and add_group for the default group
6060 double_t = "double"
6161
6262 id = 0
63
64
65 def check_description(description):
66 quotes = ['"', "'"]
67 for quote in quotes:
68 if description.find(quote) != -1:
69 raise Exception(r"""quotes not allowed in description string `%s`""" % description)
70
71
72 def check_name(name):
73 pattern = r'^[a-zA-Z][a-zA-Z0-9_]*$'
74 if not re.match(pattern, name):
75 raise Exception("The name of field \'%s\' does not follow the ROS naming conventions, see http://wiki.ros.org/ROS/Patterns/Conventions"%name)
76
6377
6478 class ParameterGenerator:
6579 minval = {
125139 }
126140 if type == str_t and (max != None or min != None):
127141 raise Exception("Max or min specified for %s, which is of string type"%name)
128 pattern = r'^[a-zA-Z][a-zA-Z0-9_]*$'
129 if not re.match(pattern, name):
130 raise Exception("The name of field \'%s\' does not follow the ROS naming conventions, see http://wiki.ros.org/ROS/Patterns/Conventions"%name)
131
142 check_name(name)
132143 self.gen.fill_type(newparam)
133144 self.gen.check_type_fill_default(newparam, 'default', self.gen.defval[paramtype])
134145 self.gen.check_type_fill_default(newparam, 'max', self.gen.maxval[paramtype])
264275 'srcfile' : inspect.getsourcefile(inspect.currentframe().f_back.f_code),
265276 'description' : descr
266277 }
278 check_description(descr)
267279 self.fill_type(newconst)
268280 self.check_type(newconst, 'value')
269281 self.constants.append(newconst)
272284 def enum(self, constants, description):
273285 if len(set(const['type'] for const in constants)) != 1:
274286 raise Exception("Inconsistent types in enum!")
287 check_description(description)
275288 return repr({ 'enum' : constants, 'enum_description' : description })
276289
277290 # Wrap add and add_group for the default group
560573 # print >> f, self.msgname, "config", "# What the node's configuration was actually set to."
561574 # f.close()
562575
576 def _rreplace_str_with_val_in_dict(self, orig_dict, old_str, new_val):
577 # Recursively replace any match of old_str by new_val in a dictionary
578 for k, v in orig_dict.items():
579 if isinstance(v, dict):
580 self._rreplace_str_with_val_in_dict(v, old_str, new_val)
581 elif isinstance(v, list):
582 for idx, i in enumerate(v):
583 if isinstance(i, str) and i == old_str:
584 orig_dict[k][idx] = new_val
585 elif isinstance(i, dict):
586 self._rreplace_str_with_val_in_dict(i, old_str, new_val)
587 elif isinstance(v, str) and v == old_str:
588 orig_dict[k] = new_val
589 return orig_dict
590
591 def replace_infinity(self, config_dict):
592 config_dict = self._rreplace_str_with_val_in_dict(config_dict, '-std::numeric_limits<double>::infinity()', -float("inf"))
593 config_dict = self._rreplace_str_with_val_in_dict(config_dict, 'std::numeric_limits<double>::infinity()', float("inf"))
594
595 return config_dict
596
563597 def generatepy(self):
564598 # Read the configuration manipulator template and insert line numbers and file name into template.
565599 templatefile = os.path.join(self.dynconfpath, "templates", "ConfigType.py.template")
571605 # Write the configuration manipulator.
572606 self.mkdirabs(os.path.join(self.py_gen_dir, "cfg"))
573607 f = open(os.path.join(self.py_gen_dir, "cfg", self.name+"Config.py"), 'w')
608 pycfgdata = self.replace_infinity(self.group.to_dict())
574609 f.write(Template(template).substitute(name = self.name,
575 pkgname = self.pkgname, pycfgdata = self.group.to_dict()))
610 pkgname = self.pkgname, pycfgdata = pycfgdata))
576611 for const in self.constants:
577612 f.write(Template("${configname}_${name} = $v\n").
578613 substitute(const, v = repr(const['value']),
5454 class ParamDescription : public AbstractParamDescription
5555 {
5656 public:
57 ParamDescription(std::string name, std::string type, uint32_t level,
58 std::string description, std::string edit_method, T ${configname}Config::* f) :
59 AbstractParamDescription(name, type, level, description, edit_method),
60 field(f)
57 ParamDescription(std::string a_name, std::string a_type, uint32_t a_level,
58 std::string a_description, std::string a_edit_method, T ${configname}Config::* a_f) :
59 AbstractParamDescription(a_name, a_type, a_level, a_description, a_edit_method),
60 field(a_f)
6161 {}
6262
6363 T (${configname}Config::* field);
140140 class GroupDescription : public AbstractGroupDescription
141141 {
142142 public:
143 GroupDescription(std::string name, std::string type, int parent, int id, bool s, T PT::* f) : AbstractGroupDescription(name, type, parent, id, s), field(f)
143 GroupDescription(std::string a_name, std::string a_type, int a_parent, int a_id, bool a_s, T PT::* a_f) : AbstractGroupDescription(a_name, a_type, a_parent, a_id, a_s), field(a_f)
144144 {
145145 }
146146
338338 template <> // Max and min are ignored for strings.
339339 inline void ${configname}Config::ParamDescription<std::string>::clamp(${configname}Config &config, const ${configname}Config &max, const ${configname}Config &min) const
340340 {
341 (void) config;
342 (void) min;
343 (void) max;
341344 return;
342345 }
343346
33
44 add_dependencies(tests dynamic_reconfigure-ref_server)
55
6 add_rostest_gtest(dynamic_reconfigure-test_client test_cpp_simple_client.launch test_client.cpp)
7 add_dependencies(dynamic_reconfigure-test_client ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_generate_messages_py)
8 target_link_libraries(dynamic_reconfigure-test_client pthread dynamic_reconfigure_config_init_mutex ${catkin_LIBRARIES})
9
10 add_dependencies(tests dynamic_reconfigure-test_client)
11
612 add_rostest(test_python_simple_client.launch)
3535 import rospy
3636 import dynamic_reconfigure.client
3737
38
3839 class TestSimpleDynamicReconfigureClient(unittest.TestCase):
3940
4041 def testsimple(self):
4445 self.assertEqual(0.0, config['double_'])
4546 self.assertEqual('foo', config['str_'])
4647 self.assertEqual(False, config['bool_'])
48 self.assertEqual(1.0, config['double_no_minmax'])
49 self.assertEqual(2.0, config['double_no_max'])
50 self.assertEqual(-1.0, config['deep_var_double'])
51
4752
4853 int_ = 7
4954 double_ = 0.75
5055 str_ = 'bar'
5156 bool_ = True
57 double_no_max_ = 1e+300
58 double_no_minmax_ = -1e+300
5259
5360 client.update_configuration(
5461 {"int_": int_, "double_": double_, "str_": str_,
55 "bool_": bool_}
62 "bool_": bool_,
63 "double_no_max": double_no_max_, "double_no_minmax": double_no_minmax_}
5664 )
5765
5866 rospy.sleep(1.0)
6472 self.assertEqual(str_, config['str_'])
6573 self.assertEqual(type(str_), type(config['str_']))
6674 self.assertEqual(bool_, config['bool_'])
75 self.assertEqual(double_no_max_, config['double_no_max'])
76 self.assertEqual(double_no_minmax_, config['double_no_minmax'])
6777
6878 def testmultibytestring(self):
6979 client = dynamic_reconfigure.client.Client("ref_server", timeout=5)
0 /*********************************************************************
1 * Software License Agreement (BSD License)
2 *
3 * Copyright (c) 2015-2016, Myrmex, Inc.
4 * All rights reserved.
5 *
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions
8 * are met:
9 *
10 * * Redistributions of source code must retain the above copyright
11 * notice, this list of conditions and the following disclaimer.
12 * * Redistributions in binary form must reproduce the above
13 * copyright notice, this list of conditions and the following
14 * disclaimer in the documentation and/or other materials provided
15 * with the distribution.
16 * * Neither the name of the Willow Garage nor the names of its
17 * contributors may be used to endorse or promote products derived
18 * from this software without specific prior written permission.
19 *
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
32 *********************************************************************/
33
34 /**
35
36 Author: Aris Synodinos
37
38 Handles sychronizing node state with the ActionServer and setting/getting
39 configuration.
40
41 */
42
43 #include <ros/ros.h>
44 #include <gtest/gtest.h>
45 #include <dynamic_reconfigure/client.h>
46 #include <dynamic_reconfigure/TestConfig.h>
47
48 using namespace dynamic_reconfigure;
49 using namespace dynamic_reconfigure_test;
50
51 TestConfig CONFIG;
52 ConfigDescription DESCRIPTION;
53
54 void configurationCallback(const TestConfig& config) {
55 ROS_INFO(
56 "Reconfiguration happened: %i %f %s %s %i %i Group1: %i Group2: %f %s",
57 config.int_, config.double_, config.str_.c_str(), config.mstr_.c_str(),
58 (int)config.bool_, config.level, config.group1_int, config.group2_double,
59 config.group2_string.c_str());
60 CONFIG = config;
61 }
62
63 void descriptionCallback(const ConfigDescription& description) {
64 ROS_INFO("Received description");
65 }
66
67 TEST(dynamic_reconfigure_simple_client, Constructor) {
68 Client<TestConfig> client("/ref_server");
69 client.setConfigurationCallback(&configurationCallback);
70 client.setDescriptionCallback(&descriptionCallback);
71 }
72
73 TEST(dynamic_reconfigure_simple_client, getConfigs) {
74 Client<TestConfig> client("/ref_server", &configurationCallback,
75 &descriptionCallback);
76 EXPECT_TRUE(client.getCurrentConfiguration(CONFIG));
77 EXPECT_TRUE(client.getDefaultConfiguration(CONFIG));
78 EXPECT_EQ(0, CONFIG.int_);
79 EXPECT_TRUE(client.getMinConfiguration(CONFIG));
80 EXPECT_EQ(-10, CONFIG.int_);
81 EXPECT_TRUE(client.getMaxConfiguration(CONFIG));
82 EXPECT_EQ(10, CONFIG.int_);
83 }
84
85 TEST(dynamic_reconfigure_simple_client, setConfig) {
86 ROS_INFO("Setting configuration");
87 Client<TestConfig> client("/ref_server", &configurationCallback,
88 &descriptionCallback);
89 TestConfig cfg = TestConfig::__getMax__();
90 EXPECT_TRUE(client.setConfiguration(cfg));
91 // int_ goes from -10 to +10
92 cfg.int_ = -11;
93 EXPECT_TRUE(client.setConfiguration(cfg));
94 EXPECT_EQ(-10, cfg.int_);
95 cfg.int_ = 11;
96 EXPECT_TRUE(client.setConfiguration(cfg));
97 EXPECT_EQ(10, cfg.int_);
98 }
99
100 TEST(dynamic_reconfigure_simple_client, setGetConfig) {
101 ROS_INFO("Setting configuration");
102 Client<TestConfig> client("/ref_server", &configurationCallback,
103 &descriptionCallback);
104 TestConfig cfg = TestConfig::__getMax__();
105 EXPECT_TRUE(client.setConfiguration(cfg));
106 // int_ goes from -10 to +10
107 cfg.int_ = -11;
108 EXPECT_TRUE(client.setConfiguration(cfg));
109 EXPECT_EQ(-10, cfg.int_);
110 EXPECT_TRUE(client.getCurrentConfiguration(CONFIG));
111 EXPECT_EQ(-10, CONFIG.int_);
112 cfg.int_ = 11;
113 EXPECT_TRUE(client.setConfiguration(cfg));
114 EXPECT_TRUE(client.getCurrentConfiguration(CONFIG));
115 EXPECT_EQ(10, CONFIG.int_);
116 cfg.int_ = 5;
117 EXPECT_TRUE(client.setConfiguration(cfg));
118 EXPECT_TRUE(client.getCurrentConfiguration(CONFIG));
119 EXPECT_EQ(5, CONFIG.int_);
120 }
121
122 TEST(dynamic_reconfigure_simple_client, multipleClients) {
123 Client<TestConfig> client1("/ref_server", &configurationCallback);
124 Client<TestConfig> client2("/ref_server", &configurationCallback);
125 Client<TestConfig> client3("/ref_server", &configurationCallback);
126 client3.setConfiguration(TestConfig::__getDefault__());
127 ros::Duration(0.2).sleep();
128 EXPECT_EQ(0, CONFIG.int_);
129 client1.setConfiguration(TestConfig::__getMin__());
130 ros::Duration(0.2).sleep();
131 EXPECT_EQ(-10, CONFIG.int_);
132 client2.setConfiguration(TestConfig::__getMax__());
133 ros::Duration(0.2).sleep();
134 EXPECT_EQ(10, CONFIG.int_);
135 }
136
137 int main(int argc, char** argv) {
138 ros::init(argc, argv, "dynamic_reconfigure_client_test");
139 testing::InitGoogleTest(&argc, argv);
140 ros::AsyncSpinner spinner(2);
141 spinner.start();
142 return RUN_ALL_TESTS();
143 }
0 <launch>
1 <node pkg="dynamic_reconfigure" type="dynamic_reconfigure-ref_server" name="ref_server" output="screen" />
2
3 <test test-name="simple_cpp_client_test" pkg="dynamic_reconfigure" type="dynamic_reconfigure-test_client" />
4 </launch>