parameter_generator_catkin.py
Go to the documentation of this file.
1 # Copyright (c) 2016, Claudio Bandera
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions are met:
6 # * Redistributions of source code must retain the above copyright
7 # notice, this list of conditions and the following disclaimer.
8 # * Redistributions in binary form must reproduce the above copyright
9 # notice, this list of conditions and the following disclaimer in the
10 # documentation and/or other materials provided with the distribution.
11 # * Neither the name of the organization nor the
12 # names of its contributors may be used to endorse or promote products
13 # derived from this software without specific prior written permission.
14 #
15 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
16 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
17 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
18 # DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
19 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
20 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
21 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
22 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
23 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
24 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
25 #
26 # Author: Claudio Bandera
27 #
28 
29 from __future__ import print_function
30 from string import Template
31 import sys
32 import os
33 import re
34 
35 
36 def eprint(*args, **kwargs):
37  print("************************************************", file=sys.stderr, **kwargs)
38  print("Error when setting up parameter '{}':".format(args[0]), file=sys.stderr, **kwargs)
39  print(*args[1:], file=sys.stderr, **kwargs)
40  print("************************************************", file=sys.stderr, **kwargs)
41  sys.exit(1)
42 
43 
44 class ParameterGenerator(object):
45  """Automatic config file and header generator"""
46 
47  def __init__(self, parent=None, group=""):
48  """Constructor for ParamGenerator"""
49  self.enums = []
50  self.parameters = []
51  self.childs = []
52  self.parent = parent
53  if group:
54  self.group = group
55  else:
56  self.group = "gen"
57  self.group_variable = filter(str.isalnum, self.group)
58 
59  if len(sys.argv) != 5:
60  eprint(
61  "ParameterGenerator: Unexpected amount of args, did you try to call this directly? You shouldn't do this!")
62 
63  self.dynconfpath = sys.argv[1]
64  self.share_dir = sys.argv[2]
65  self.cpp_gen_dir = sys.argv[3]
66  self.py_gen_dir = sys.argv[4]
67 
68  self.pkgname = None
69  self.nodename = None
70  self.classname = None
71 
72  def add_group(self, name):
73  """
74  Add a new group in the dynamic reconfigure selection
75  :param name: name of the new group
76  :return: a new group object that you can add parameters to
77  """
78  if not name:
79  eprint("You have added a group with an empty group name. This is not supported!")
80  child = ParameterGenerator(self, name)
81  self.childs.append(child)
82  return child
83 
84  def add_enum(self, name, description, entry_strings, default=None):
85  """
86  Add an enum to dynamic reconfigure
87  :param name: Name of enum parameter
88  :param description: Informative documentation string
89  :param entry_strings: Enum entries, must be strings! (will be numbered with increasing value)
90  :param default: Default value
91  :return:
92  """
93 
94  entry_strings = [str(e) for e in entry_strings] # Make sure we only get strings
95  if default is None:
96  default = 0
97  else:
98  default = entry_strings.index(default)
99  self.add(name=name, paramtype="int", description=description, edit_method=name, default=default,
100  configurable=True)
101  for e in entry_strings:
102  self.add(name=name + "_" + e, paramtype="int", description="Constant for enum {}".format(name),
103  default=entry_strings.index(e), constant=True)
104  self.enums.append({'name': name, 'description': description, 'values': entry_strings})
105 
106  def add(self, name, paramtype, description, level=0, edit_method='""', default=None, min=None, max=None,
107  configurable=False, global_scope=False, constant=False):
108  """
109  Add parameters to your parameter struct. Call this method from your .params file!
110 
111  - If no default value is given, you need to specify one in your launch file
112  - Global parameters, vectors, maps and constant params can not be configurable
113 
114  :param self:
115  :param name: The Name of you new parameter
116  :param paramtype: The C++ type of this parameter. Can be any of ['std::string', 'int', 'bool', 'float',
117  'double'] or std::vector<...> or std::map<std::string, ...>
118  :param description: Choose an informative documentation string for this parameter.
119  :param level: (optional) Passed to dynamic_reconfigure
120  :param edit_method: (optional) Passed to dynamic_reconfigure
121  :param default: (optional) default value
122  :param min: (optional)
123  :param max: (optional)
124  :param configurable: (optional) Should this parameter be dynamic configurable
125  :param global_scope: (optional) If true, parameter is searched in global ('/') namespace instead of private (
126  '~') ns
127  :param constant: (optional) If this is true, the parameter will not be fetched from param server,
128  but the default value is kept.
129  :return: None
130  """
131  configurable = self._make_bool(configurable)
132  global_scope = self._make_bool(global_scope)
133  constant = self._make_bool(constant)
134  newparam = {
135  'name': name,
136  'type': paramtype,
137  'default': default,
138  'level': level,
139  'edit_method': edit_method,
140  'description': description,
141  'min': min,
142  'max': max,
143  'is_vector': False,
144  'is_map': False,
145  'configurable': configurable,
146  'constant': constant,
147  'global_scope': global_scope,
148  }
149  self._perform_checks(newparam)
150  self.parameters.append(newparam)
151 
152  def _perform_checks(self, param):
153  """
154  Will test some logical constraints as well as correct types.
155  Throws Exception in case of error.
156  :param self:
157  :param param: Dictionary of one param
158  :return:
159  """
160 
161  in_type = param['type'].strip()
162  if param['max'] is not None or param['min'] is not None:
163  if in_type in ["std::string", "bool"]:
164  eprint(param['name'], "Max and min can not be specified for variable of type %s" % in_type)
165 
166  if in_type.startswith('std::vector'):
167  param['is_vector'] = True
168  if in_type.startswith('std::map'):
169  param['is_map'] = True
170 
171  if (param['is_vector']):
172  if (param['max'] is not None or param['min'] is not None):
173  ptype = in_type[12:-1].strip()
174  if ptype == "std::string":
175  eprint(param['name'], "Max and min can not be specified for variable of type %s" % in_type)
176 
177  if (param['is_map']):
178  if (param['max'] is not None or param['min'] is not None):
179  ptype = in_type[9:-1].split(',')
180  if len(ptype) != 2:
181  eprint(param['name'],
182  "Wrong syntax used for setting up std::map<... , ...>: You provided '%s' with "
183  "parameter %s" % in_type)
184  ptype = ptype[1].strip()
185  if ptype == "std::string":
186  eprint(param['name'], "Max and min can not be specified for variable of type %s" % in_type)
187 
188  pattern = r'^[a-zA-Z][a-zA-Z0-9_]*$'
189  if not re.match(pattern, param['name']):
190  eprint(param['name'], "The name of field does not follow the ROS naming conventions, "
191  "see http://wiki.ros.org/ROS/Patterns/Conventions")
192  if param['configurable'] and (
193  param['global_scope'] or param['is_vector'] or param['is_map'] or param['constant']):
194  eprint(param['name'],
195  "Global Parameters, vectors, maps and constant params can not be declared configurable! ")
196  if param['global_scope'] and param['default'] is not None:
197  eprint(param['name'], "Default values for global parameters should not be specified in node! ")
198  if param['constant'] and param['default'] is None:
199  eprint(param['name'], "Constant parameters need a default value!")
200  if param['name'] in [p['name'] for p in self.parameters]:
201  eprint(param['name'], "Parameter with the same name exists already")
202  if param['edit_method'] == '':
203  param['edit_method'] = '""'
204  elif param['edit_method'] != '""':
205  param['configurable'] = True
206 
207  # Check type
208  if param['is_vector']:
209  ptype = in_type[12:-1].strip()
210  self._test_primitive_type(param['name'], ptype)
211  param['type'] = 'std::vector<{}>'.format(ptype)
212  elif param['is_map']:
213  ptype = in_type[9:-1].split(',')
214  if len(ptype) != 2:
215  eprint(param['name'], "Wrong syntax used for setting up std::map<... , ...>: You provided '%s' with "
216  "parameter %s" % in_type)
217  ptype[0] = ptype[0].strip()
218  ptype[1] = ptype[1].strip()
219  if ptype[0] != "std::string":
220  eprint(param['name'], "Can not setup map with %s as key type. Only std::map<std::string, "
221  "...> are allowed" % ptype[0])
222  self._test_primitive_type(param['name'], ptype[0])
223  self._test_primitive_type(param['name'], ptype[1])
224  param['type'] = 'std::map<{},{}>'.format(ptype[0], ptype[1])
225  else:
226  # Pytype and defaults can only be applied to primitives
227  self._test_primitive_type(param['name'], in_type)
228  param['pytype'] = self._pytype(in_type)
229 
230  @staticmethod
231  def _pytype(drtype):
232  """Convert C++ type to python type"""
233  return {'std::string': "str", 'int': "int", 'double': "double", 'bool': "bool"}[drtype]
234 
235  @staticmethod
236  def _test_primitive_type(name, drtype):
237  """
238  Test whether parameter has one of the accepted C++ types
239  :param name: Parametername
240  :param drtype: Typestring
241  :return:
242  """
243  primitive_types = ['std::string', 'int', 'bool', 'float', 'double']
244  if drtype not in primitive_types:
245  raise TypeError("'%s' has type %s, but allowed are: %s" % (name, drtype, primitive_types))
246 
247  @staticmethod
248  def _get_cvalue(param, field):
249  """
250  Helper function to convert strings and booleans to correct C++ syntax
251  :param param:
252  :return: C++ compatible representation
253  """
254  value = param[field]
255  if param['type'] == 'std::string':
256  value = '"{}"'.format(param[field])
257  elif param['type'] == 'bool':
258  value = str(param[field]).lower()
259  return str(value)
260 
261  @staticmethod
262  def _get_pyvalue(param, field):
263  """
264  Helper function to convert strings and booleans to correct C++ syntax
265  :param param:
266  :return: C++ compatible representation
267  """
268  value = param[field]
269  if param['type'] == 'std::string':
270  value = '"{}"'.format(param[field])
271  elif param['type'] == 'bool':
272  value = str(param[field]).capitalize()
273  return str(value)
274 
275  @staticmethod
276  def _get_cvaluelist(param, field):
277  """
278  Helper function to convert python list of strings and booleans to correct C++ syntax
279  :param param:
280  :return: C++ compatible representation
281  """
282  values = param[field]
283  assert (isinstance(values, list))
284  form = ""
285  for value in values:
286  if param['type'] == 'std::vector<std::string>':
287  value = '"{}"'.format(value)
288  elif param['type'] == 'std::vector<bool>':
289  value = str(value).lower()
290  else:
291  value = str(value)
292  form += value + ','
293  # remove last ','
294  return form[:-1]
295 
296  @staticmethod
297  def _get_cvaluedict(param, field):
298  """
299  Helper function to convert python dict of strings and booleans to correct C++ syntax
300  :param param:
301  :return: C++ compatible representation
302  """
303  values = param[field]
304  assert (isinstance(values, dict))
305  form = ""
306  for key, value in values.items():
307  if param['type'] == 'std::map<std::string,std::string>':
308  pair = '{{"{}","{}"}}'.format(key, value)
309  elif param['type'] == 'std::map<std::string,bool>':
310  pair = '{{"{}",{}}}'.format(key, str(value).lower())
311  else:
312  pair = '{{"{}",{}}}'.format(key, str(value))
313  form += pair + ','
314  # remove last ','
315  return form[:-1]
316 
317  def generate(self, pkgname, nodename, classname):
318  """
319  Main working Function, call this at the end of your .params file!
320  :param self:
321  :param pkgname: Name of the catkin package
322  :param nodename: Name of the Node that will hold these params
323  :param classname: This should match your file name, so that cmake will detect changes in config file.
324  :return: Exit Code
325  """
326  self.pkgname = pkgname
327  self.nodename = nodename
328  self.classname = classname
329 
330  if self.parent:
331  eprint("You should not call generate on a group! Call it on the main parameter generator instead!")
332 
333  return self._generateImpl()
334 
335  def _generateImpl(self):
336  """
337  Implementation level function. Can be overwritten by derived classes.
338  :return:
339  """
340  self._generatecfg()
341  self._generatehpp()
342  self._generatepy()
343 
344  return 0
345 
346  def _generatecfg(self):
347  """
348  Generate .cfg file for dynamic reconfigure
349  :param self:
350  :return:
351  """
352  templatefile = os.path.join(self.dynconfpath, "templates", "ConfigType.h.template")
353  with open(templatefile, 'r') as f:
354  template = f.read()
355 
356  param_entries = self._generate_param_entries()
357 
358  param_entries = "\n".join(param_entries)
359  template = Template(template).substitute(pkgname=self.pkgname, nodename=self.nodename,
360  classname=self.classname, params=param_entries)
361 
362  cfg_file = os.path.join(self.share_dir, "cfg", self.classname + ".cfg")
363  try:
364  if not os.path.exists(os.path.dirname(cfg_file)):
365  os.makedirs(os.path.dirname(cfg_file))
366  except OSError:
367  # Stupid error, sometimes the directory exists anyway
368  pass
369  with open(cfg_file, 'w') as f:
370  f.write(template)
371  os.chmod(cfg_file, 509) # entspricht 775 (octal)
372 
373  def _generatehpp(self):
374  """
375  Generate C++ Header file, holding the parameter struct.
376  :param self:
377  :return:
378  """
379 
380  # Read in template file
381  templatefile = os.path.join(self.dynconfpath, "templates", "Parameters.h.template")
382  with open(templatefile, 'r') as f:
383  template = f.read()
384 
385  param_entries = []
386  string_representation = []
387  from_server = []
388  to_server = []
389  non_default_params = []
390  from_config = []
391  to_config = []
392  test_limits = []
393 
394  params = self._get_parameters()
395 
396  # Create dynamic parts of the header file for every parameter
397  for param in params:
398  name = param['name']
399 
400  # Adjust key for parameter server
401  if param["global_scope"]:
402  namespace = 'globalNamespace'
403  else:
404  namespace = 'privateNamespace'
405  full_name = '{} + "{}"'.format(namespace, param["name"])
406 
407  # Test for default value
408  if param["default"] is None:
409  default = ""
410  non_default_params.append(Template(' << "\t" << $namespace << "$name" << " ($type) '
411  '\\n"\n').substitute(
412  namespace=namespace, name=name, type=param["type"]))
413  else:
414  if param['is_vector']:
415  default = ', {}'.format(str(param['type']) + "{" + self._get_cvaluelist(param, "default") + "}")
416  elif param['is_map']:
417  default = ', {}'.format(str(param['type']) + "{" + self._get_cvaluedict(param, "default") + "}")
418  else:
419  default = ', {}'.format(str(param['type']) + "{" + self._get_cvalue(param, "default") + "}")
420 
421  # Test for constant value
422  if param['constant']:
423  param_entries.append(Template(' static constexpr auto ${name} = $default; /*!< ${description} '
424  '*/').substitute(type=param['type'], name=name,
425  description=param['description'],
426  default=self._get_cvalue(param, "default")))
427  from_server.append(Template(' rosparam_handler::testConstParam($paramname);').substitute(paramname=full_name))
428  else:
429  param_entries.append(Template(' ${type} ${name}; /*!< ${description} */').substitute(
430  type=param['type'], name=name, description=param['description']))
431  from_server.append(Template(' success &= rosparam_handler::getParam($paramname, $name$default);').substitute(
432  paramname=full_name, name=name, default=default, description=param['description']))
433  to_server.append(
434  Template(' rosparam_handler::setParam(${paramname},${name});').substitute(paramname=full_name, name=name))
435 
436  # Test for configurable params
437  if param['configurable']:
438  from_config.append(Template(' $name = config.$name;').substitute(name=name))
439  to_config.append(Template(' config.$name = $name;').substitute(name=name))
440 
441  # Test limits
442  if param['is_vector']:
443  ttype = param['type'][12:-1].strip()
444  elif param['is_map']:
445  ttype = param['type'][9:-1].strip()
446  else:
447  ttype = param['type']
448  if param['min'] is not None:
449  test_limits.append(Template(' rosparam_handler::testMin<$type>($paramname, $name, $min);').substitute(
450  paramname=full_name, name=name, min=param['min'], type=ttype))
451  if param['max'] is not None:
452  test_limits.append(Template(' rosparam_handler::testMax<$type>($paramname, $name, $max);').substitute(
453  paramname=full_name, name=name, max=param['max'], type=ttype))
454 
455  # Add debug output
456  if param['is_vector'] or param['is_map']:
457  string_representation.append(Template(' << "\t" << p.$namespace << "$name:" << rosparam_handler::to_string(p.$name) << '
458  '"\\n"\n').substitute(namespace=namespace, name=name))
459  else:
460  string_representation.append(Template(' << "\t" << p.$namespace << "$name:" << p.$name << '
461  '"\\n"\n').substitute(namespace=namespace, name=name))
462 
463  param_entries = "\n".join(param_entries)
464  string_representation = "".join(string_representation)
465  non_default_params = "".join(non_default_params)
466  from_server = "\n".join(from_server)
467  to_server = "\n".join(to_server)
468  from_config = "\n".join(from_config)
469  to_config = "\n".join(to_config)
470  test_limits = "\n".join(test_limits)
471 
472  content = Template(template).substitute(pkgname=self.pkgname, ClassName=self.classname,
473  parameters=param_entries, fromConfig=from_config,
474  fromParamServer=from_server,
475  string_representation=string_representation,
476  non_default_params=non_default_params, nodename=self.nodename,
477  test_limits=test_limits, toParamServer=to_server,
478  toConfig=to_config)
479 
480  header_file = os.path.join(self.cpp_gen_dir, self.classname + "Parameters.h")
481  try:
482  if not os.path.exists(os.path.dirname(header_file)):
483  os.makedirs(os.path.dirname(header_file))
484  except OSError:
485  # Stupid error, sometimes the directory exists anyway
486  pass
487  with open(header_file, 'w') as f:
488  f.write(content)
489 
490  def _generatepy(self):
491  """
492  Generate Python parameter file
493  :param self:
494  :return:
495  """
496  params = self._get_parameters()
497  paramDescription = str(params)
498 
499  # Read in template file
500  templatefile = os.path.join(self.dynconfpath, "templates", "Parameters.py.template")
501  with open(templatefile, 'r') as f:
502  template = f.read()
503 
504  content = Template(template).substitute(pkgname=self.pkgname, ClassName=self.classname,
505  paramDescription=paramDescription)
506 
507  py_file = os.path.join(self.py_gen_dir, "param", self.classname + "Parameters.py")
508  try:
509  if not os.path.exists(os.path.dirname(py_file)):
510  os.makedirs(os.path.dirname(py_file))
511  except OSError:
512  # Stupid error, sometimes the directory exists anyway
513  pass
514  with open(py_file, 'w') as f:
515  f.write(content)
516  init_file = os.path.join(self.py_gen_dir, "param", "__init__.py")
517  with open(init_file, 'wa') as f:
518  f.write("")
519 
520  def _generateyml(self):
521  """
522  Generate .yaml file for roslaunch
523  :param self:
524  :return:
525  """
526  params = self._get_parameters()
527 
528  content = "### This file was generated using the rosparam_handler generate_yaml script.\n"
529 
530  for entry in params:
531  if not entry["constant"]:
532  content += "\n"
533  content += "# Name:\t" + str(entry["name"]) + "\n"
534  content += "# Desc:\t" + str(entry["description"]) + "\n"
535  content += "# Type:\t" + str(entry["type"]) + "\n"
536  if entry['min'] or entry['max']:
537  content += "# [min,max]:\t[" + str(entry["min"]) + "/" + str(entry["max"]) + "]" + "\n"
538  if entry["global_scope"]:
539  content += "# Lives in global namespace!\n"
540  if entry["default"] is not None:
541  content += str(entry["name"]) + ": " + str(entry["default"]) + "\n"
542  else:
543  content += str(entry["name"]) + ": \n"
544 
545  yaml_file = os.path.join(os.getcwd(), self.classname + "Parameters.yaml")
546 
547  with open(yaml_file, 'w') as f:
548  f.write(content)
549 
550  def _get_parameters(self):
551  """
552  Returns parameter of this and all childs
553  :return: list of all parameters
554  """
555  params = self.parameters
556  for child in self.childs:
557  params.extend(child._get_parameters())
558  return params
559 
561  """
562  Generates the entries for the cfg-file
563  :return: list of param entries as string
564  """
565  param_entries = []
566  dynamic_params = [p for p in self.parameters if p["configurable"]]
567 
568  if self.parent:
569  param_entries.append(Template("$group_variable = $parent.add_group('$group')").substitute(
570  group_variable=self.group_variable,
571  group=self.group,
572  parent=self.parent.group_variable))
573 
574  for enum in self.enums:
575  param_entries.append(Template("$name = gen.enum([").substitute(
576  name=enum['name'],
577  parent=self.group))
578  i = 0
579  for value in enum['values']:
580  param_entries.append(
581  Template(" gen.const(name='$name', type='$type', value=$value, descr='$descr'),")
582  .substitute(name=value, type="int", value=i, descr=""))
583  i += 1
584  param_entries.append(Template(" ], '$description')").substitute(description=enum["description"]))
585 
586  for param in dynamic_params:
587  content_line = Template("$group_variable.add(name = '$name', paramtype = '$paramtype', level = $level, "
588  "description = '$description', edit_method=$edit_method").substitute(
589  group_variable=self.group_variable,
590  name=param["name"],
591  paramtype=param['pytype'],
592  level=param['level'],
593  edit_method=param['edit_method'],
594  description=param['description'])
595  if param['default'] is not None:
596  content_line += Template(", default=$default").substitute(default=self._get_pyvalue(param, "default"))
597  if param['min'] is not None:
598  content_line += Template(", min=$min").substitute(min=param['min'])
599  if param['max'] is not None:
600  content_line += Template(", max=$max").substitute(max=param['max'])
601  content_line += ")"
602  param_entries.append(content_line)
603 
604  for child in self.childs:
605  param_entries.extend(child._generate_param_entries())
606  return param_entries
607 
608  @staticmethod
609  def _make_bool(param):
610  if isinstance(param, bool):
611  return param
612  else:
613  # Pray and hope that it is a string
614  return bool(param)
615 
616 
617 # Create derived class for yaml generation
619  def _generateImpl(self):
620  self._generateyml()
621  return 0
def add(self, name, paramtype, description, level=0, edit_method='""', default=None, min=None, max=None, configurable=False, global_scope=False, constant=False)
def add_enum(self, name, description, entry_strings, default=None)


rosparam_handler
Author(s): Claudio Bandera
autogenerated on Mon Jun 10 2019 14:48:10