1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35 """
36 Implementation of the rosparam as well as a library for modifying the
37 state of the ROS Parameter Server using YAML files.
38 """
39
40 from __future__ import print_function
41
42 NAME = 'rosparam'
43
44
45
46
47
48 NS = '_ns'
49
50 import base64
51 import math
52 import os
53 import re
54 import sys
55 import socket
56 import xmlrpclib
57
58 from optparse import OptionParser
59
60 import yaml
61
62 import rosgraph
63 from rosgraph.names import script_resolve_name, ns_join, get_ros_namespace, make_caller_id, make_global_ns, GLOBALNS
64
66 """
67 rosparam base exception type
68 """
69 pass
71 """
72 Exception for communication-based (i/o) errors.
73 """
74 pass
75
76
77
79 """
80 Adds a pyyaml serializer to handle xmlrpclib.Binary objects
81 """
82 data = base64.b64encode(data.data)
83 return loader.represent_scalar(u'tag:yaml.org,2002:binary', data, style='|')
84
86 return loader.represent_scalar(u'#', data)
87
89 """
90 Overrides pyaml's constructor for binary data. Wraps binary data in
91 xmlrpclib.Binary container instead of straight string
92 representation.
93 """
94 return xmlrpclib.Binary(loader.construct_yaml_binary(node))
95
96
97 yaml.add_representer(xmlrpclib.Binary,represent_xml_binary)
98 yaml.add_constructor(u'tag:yaml.org,2002:binary', construct_yaml_binary)
99
101 """
102 python-yaml utility for converting rad(num) into float value
103 """
104 value = loader.construct_scalar(node).strip()
105 exprvalue = value.replace('pi', 'math.pi')
106 if exprvalue.startswith("rad("):
107 exprvalue = exprvalue[4:-1]
108 try:
109 return float(eval(exprvalue))
110 except SyntaxError as e:
111 raise RosParamException("invalid radian expression: %s"%value)
112
114 """
115 python-yaml utility for converting deg(num) into float value
116 """
117 value = loader.construct_scalar(node)
118 exprvalue = value
119 if exprvalue.startswith("deg("):
120 exprvalue = exprvalue.strip()[4:-1]
121 try:
122 return float(exprvalue) * math.pi / 180.0
123 except ValueError:
124 raise RosParamException("invalid degree value: %s"%value)
125
126
127
128
130 """
131 :returns: caller ID for rosparam ROS client calls, ``str``
132 """
133 return make_caller_id('rosparam-%s'%os.getpid())
134
136 """
137 Print contents of param dictionary to screen
138 """
139 if type(params) == dict:
140 for k, v in params.iteritems():
141 if type(v) == dict:
142 print_params(v, ns_join(ns, k))
143 else:
144 print("%s=%s"%(ns_join(ns, k), v))
145 else:
146 print(params)
147
148
149
150 -def load_file(filename, default_namespace=None, verbose=False):
151 """
152 Load the YAML document from the specified file
153
154 :param filename: name of filename, ``str``
155 :param default_namespace: namespace to load filename into, ``str``
156 :returns [(dict, str)...]: list of parameter dictionary and
157 corresponding namespaces for each YAML document in the file
158 :raises: :exc:`RosParamException`: if unable to load contents of filename
159 """
160 if not os.path.isfile(filename):
161 raise RosParamException("file [%s] does not exist"%filename)
162 if verbose:
163 print("reading parameters from [%s]"%filename)
164 f = open(filename, 'r')
165 try:
166 return load_str(f.read(), filename, default_namespace=default_namespace, verbose=verbose)
167 finally:
168 f.close()
169
170 -def load_str(str, filename, default_namespace=None, verbose=False):
171 """
172 Load the YAML document as a string
173
174 :param filename: name of filename, only used for debugging, ``str``
175 :param default_namespace: namespace to load filename into, ``str``
176 :param str: YAML text, ``str``
177 :returns: list of parameter dictionary and
178 corresponding namespaces for each YAML document in the file, ``[(dict, str)...]``
179 """
180 paramlist = []
181 default_namespace = default_namespace or get_ros_namespace()
182 for doc in yaml.load_all(str):
183 if NS in doc:
184 ns = ns_join(default_namespace, doc.get(NS, None))
185 if verbose:
186 print("reading parameters into namespace [%s]"%ns)
187 del doc[NS]
188 else:
189 ns = default_namespace
190 paramlist.append((doc, ns))
191 return paramlist
192
193
194
195
197 return rosgraph.Master(_get_caller_id())
198
200 """
201 Download a parameter from Parameter Server
202
203 :param param: parameter name to retrieve from parameter
204 server. If param is a parameter namespace, entire parameter
205 subtree will be downloaded, ``str``
206 """
207 try:
208 return get_param_server().getParam(param)
209 except socket.error:
210 raise RosParamIOException("Unable to communicate with master!")
211
212
214 """
215 Pretty print get value
216 :param value: value to print
217 :param indent: indent level, used for recursive calls, ``str``
218 """
219 keys = value.keys()
220 keys.sort()
221 for k in keys:
222 v = value[k]
223 if type(v) == dict:
224 print("%s%s:"%(indent, k))
225 _pretty_print(v, indent+' ')
226 elif type(v) == str:
227 if '\n' in v:
228 print(indent+'%s: |'%k)
229 for l in v.split('\n'):
230 print(indent+' '+l)
231 else:
232 print("%s%s: %s"%(indent, k, v))
233 else:
234 dump = yaml.dump(v)
235
236
237
238
239
240 if dump.endswith('\n...\n'):
241 dump = dump[:-4]
242
243 sys.stdout.write("%s%s: %s"%(indent, k, dump))
244
246 """
247 Download a parameter tree and print to screen
248 :param param: parameter name to retrieve from Parameter
249 Server. If param is a parameter namespace, entire parameter
250 subtree will be downloaded, ``str``
251 """
252
253 if verbose:
254 print("getting parameter [%s]"%param)
255 try:
256 val = get_param(param)
257 except rosgraph.masterapi.Error as e:
258 raise RosParamException(str(e))
259 if pretty and type(val) in [dict, str]:
260 if type(val) == dict:
261 _pretty_print(val)
262 else:
263 if '\n' in val:
264 print('|')
265 for l in val.split('\n'):
266 print(' '+l)
267 else:
268 print(val)
269 else:
270 dump = yaml.dump(val)
271
272
273
274
275
276 if dump.endswith('\n...\n'):
277 dump = dump[:-5]
278
279
280 sys.stdout.write("%s\n"%(dump))
281
283 """
284 Download a parameter tree from the Parameter Server and store in a yaml file
285
286 :param filename: name of file to save YAML representation, ``str``
287 :param param: name of parameter/namespace to dump, ``str``
288 :param verbose: print verbose output for debugging, ``bool``
289 """
290 tree = get_param(param)
291 if verbose:
292 print_params(tree, param)
293 f = open(filename, 'w')
294 try:
295 yaml.dump(tree, f)
296 finally:
297 f.close()
298
299
301 """
302 Delete a parameter from the Parameter Server
303
304 :param param: parameter name, ``str``
305 :param verbose: print verbose output for debugging, ``bool``
306 """
307 try:
308 if param == GLOBALNS:
309
310
311
312 get_param_server().setParam(GLOBALNS, {})
313 if verbose:
314 print("deleted ENTIRE parameter server")
315 else:
316 get_param_server().deleteParam(param)
317 if verbose:
318 print("deleted parameter [%s]"%param)
319 except socket.error:
320 raise RosParamIOException("Unable to communicate with master!")
321
322
323
325 """
326 Set param on the Parameter Server. Unlike L{set_param()}, this
327 takes in a Python value to set instead of YAML.
328
329 :param param: parameter name, ``str``
330 :param value XmlRpcLegalValue: value to upload, ``XmlRpcLegalValue``
331 """
332 if type(value) == dict:
333
334
335 for k, v in value.iteritems():
336
337 if isinstance(k, str):
338 set_param_raw(ns_join(param, k), v, verbose=verbose)
339 else:
340 raise RosParamException("YAML dictionaries must have string keys. Invalid dictionary is:\n%s"%value)
341 else:
342 if type(value) == long:
343 if value > sys.maxint:
344 raise RosParamException("Overflow: Parameter Server integers must be 32-bit signed integers:\n\t-%s <= value <= %s"%(sys.maxint-1, sys.maxint))
345
346 try:
347 get_param_server().setParam(param, value)
348 except socket.error:
349 raise RosParamIOException("Unable to communicate with master!")
350 if verbose:
351 print("set parameter [%s] to [%s]"%(param, value))
352
354 """
355 Set param on the ROS parameter server using a YAML value.
356
357 :param param: parameter name, ``str``
358 :param value: yaml-encoded value, ``str``
359 """
360 set_param_raw(param, yaml.load(value), verbose=verbose)
361
363 """
364 Upload params to the Parameter Server
365 :param values: key/value dictionary, where keys are parameter names and values are parameter values, ``dict``
366 :param ns: namespace to load parameters into, ``str``
367 """
368 if ns == '/' and not type(values) == dict:
369 raise RosParamException("global / can only be set to a dictionary")
370 if verbose:
371 print_params(values, ns)
372 set_param_raw(ns, values)
373
374
375
376
378 """
379 Get list of parameters in ns
380
381 :param ns: namespace to match, ``str``
382 """
383 try:
384 ns = make_global_ns(ns)
385 names = get_param_server().getParamNames()
386 names.sort()
387 return [n for n in names if n.startswith(ns)]
388 except socket.error:
389 raise RosParamIOException("Unable to communicate with master!")
390
391
392
394 """
395 Process command line for rosparam get/dump, e.g.::
396 rosparam get param
397 rosparam dump file.yaml [namespace]
398
399 :param cmd: command ('get' or 'dump'), ``str``
400 :param argv: command-line args, ``str``
401 """
402
403 if cmd == 'dump':
404 parser = OptionParser(usage="usage: %prog dump [options] file [namespace]", prog=NAME)
405 elif cmd == 'get':
406 parser = OptionParser(usage="usage: %prog get [options] parameter", prog=NAME)
407 parser.add_option("-p", dest="pretty", default=False,
408 action="store_true", help="pretty print. WARNING: not YAML-safe")
409
410 parser.add_option("-v", dest="verbose", default=False,
411 action="store_true", help="turn on verbose output")
412 options, args = parser.parse_args(argv[2:])
413
414 arg = None
415 ns = ''
416
417 if len(args) == 0:
418 if cmd == 'dump':
419 parser.error("invalid arguments. Please specify a file name")
420 elif cmd == 'get':
421 parser.error("invalid arguments. Please specify a parameter name")
422 elif len(args) == 1:
423 arg = args[0]
424 elif len(args) == 2 and cmd == 'dump':
425 arg = args[0]
426 ns = args[1]
427 else:
428 parser.error("too many arguments")
429
430 if cmd == 'get':
431 _rosparam_cmd_get_param(script_resolve_name(NAME, arg), pretty=options.pretty, verbose=options.verbose)
432 else:
433 if options.verbose:
434 print("dumping namespace [%s] to file [%s]"%(ns, arg))
435 dump_params(arg, script_resolve_name(NAME, ns), verbose=options.verbose)
436
438
439
440
441
442 args = []
443 optparse_args = []
444 skip = False
445 for s in argv[2:]:
446 if s.startswith('-'):
447 if s in ['-t', '--textfile', '-b', '--binfile']:
448 skip = True
449 optparse_args.append(s)
450 elif skip:
451 parser.error("-t and --textfile options require an argument")
452 elif len(s) > 1 and ord(s[1]) >= ord('0') and ord(s[1]) <= ord('9'):
453 args.append(s)
454 else:
455 optparse_args.append(s)
456 else:
457 if skip:
458 skip = False
459 optparse_args.append(s)
460 else:
461 args.append(s)
462 options, _ = parser.parse_args(optparse_args)
463 return options, args
464
465
467 """
468 Process command line for rosparam set/load, e.g.::
469 rosparam load file.yaml [namespace]
470 rosparam set param value
471
472 :param cmd: command name, ``str``
473 :param argv: command-line args, ``str``
474 """
475 if cmd == 'load':
476 parser = OptionParser(usage="usage: %prog load [options] file [namespace]", prog=NAME)
477 elif cmd == 'set':
478 parser = OptionParser(usage="usage: %prog set [options] parameter value", prog=NAME)
479 parser.add_option("-t", "--textfile", dest="text_file", default=None,
480 metavar="TEXT_FILE", help="set parameters to contents of text file")
481 parser.add_option("-b", "--binfile", dest="bin_file", default=None,
482 metavar="BINARY_FILE", help="set parameters to contents of binary file")
483
484 parser.add_option("-v", dest="verbose", default=False,
485 action="store_true", help="turn on verbose output")
486 options, args = _set_optparse_neg_args(parser, argv)
487 if cmd == 'set':
488 if options.text_file and options.bin_file:
489 parser.error("you may only specify one of --textfile or --binfile")
490
491 arg2 = None
492 if len(args) == 0:
493 if cmd == 'load':
494 parser.error("invalid arguments. Please specify a file name")
495 elif cmd == 'set':
496 parser.error("invalid arguments. Please specify a parameter name")
497 elif len(args) == 1:
498 arg = args[0]
499 if cmd == 'set' and not (options.text_file or options.bin_file):
500 parser.error("invalid arguments. Please specify a parameter value")
501 elif len(args) == 2:
502 arg = args[0]
503 arg2 = args[1]
504 else:
505 parser.error("too many arguments")
506
507 if cmd == 'set':
508 name = script_resolve_name(NAME, arg)
509
510 if options.text_file:
511 if not os.path.isfile(options.text_file):
512 parser.error("file '%s' does not exist"%(options.text_file))
513 with open(options.text_file) as f:
514 arg2 = f.read()
515 set_param_raw(name, arg2, verbose=options.verbose)
516 elif options.bin_file:
517 import xmlrpclib
518 with open(options.bin_file, 'rb') as f:
519 arg2 = xmlrpclib.Binary(f.read())
520 set_param_raw(name, arg2, verbose=options.verbose)
521 else:
522
523
524
525
526
527 if arg2 == '':
528 arg2 = '!!str'
529 set_param(name, arg2, verbose=options.verbose)
530 else:
531 paramlist = load_file(arg, default_namespace=script_resolve_name(NAME, arg2), verbose=options.verbose)
532 for params,ns in paramlist:
533 upload_params(ns, params, verbose=options.verbose)
534
536 """
537 Process command line for rosparam set/load, e.g.::
538 rosparam load file.yaml [namespace]
539 rosparam set param value
540
541 :param argv: command-line args, ``str``
542 """
543 parser = OptionParser(usage="usage: %prog list [namespace]", prog=NAME)
544 options, args = parser.parse_args(argv[2:])
545
546 ns = GLOBALNS
547 if len(args) == 1:
548 ns = script_resolve_name(NAME, args[0])
549 elif len(args) == 2:
550 parser.error("too many arguments")
551
552 print('\n'.join(list_params(ns)))
553
554
556 """
557 Process command line for rosparam delete, e.g.::
558 rosparam delete param
559
560 :param cmd: command name, ``str``
561 :param argv: command-line args, ``str``
562 """
563 parser = OptionParser(usage="usage: %prog delete [options] parameter", prog=NAME)
564 parser.add_option("-v", dest="verbose", default=False,
565 action="store_true", help="turn on verbose output")
566 options, args = parser.parse_args(argv[2:])
567
568 arg2 = None
569 if len(args) == 0:
570 parser.error("invalid arguments. Please specify a parameter name")
571 elif len(args) == 1:
572 arg = args[0]
573 else:
574 parser.error("too many arguments")
575
576 try:
577 delete_param(script_resolve_name(NAME, arg), verbose=options.verbose)
578 except rosgraph.masterapi.Error as e:
579 raise RosParamException(str(e))
580
582 """
583 Prints rosparam usage
584 """
585 print("""rosparam is a command-line tool for getting, setting, and deleting parameters from the ROS Parameter Server.
586
587 Commands:
588 \trosparam set\tset parameter
589 \trosparam get\tget parameter
590 \trosparam load\tload parameters from file
591 \trosparam dump\tdump parameters to file
592 \trosparam delete\tdelete parameter
593 \trosparam list\tlist parameter names
594 """)
595 sys.exit(0)
596
597 -def yamlmain(argv=None):
598 """
599 Command-line main routine. Loads in one or more input files
600
601 :param argv: command-line arguments or None to use sys.argv, ``[str]``
602 """
603 if argv is None:
604 argv = sys.argv
605 if len(argv) == 1:
606 _fullusage()
607 try:
608 command = argv[1]
609 if command in ['get', 'dump']:
610 _rosparam_cmd_get_dump(command, argv)
611 elif command in ['set', 'load']:
612 _rosparam_cmd_set_load(command, argv)
613 elif command in ['delete']:
614 _rosparam_cmd_delete(argv)
615 elif command == 'list':
616 _rosparam_cmd_list(argv)
617 else:
618 _fullusage()
619 except RosParamException as e:
620 print("ERROR: "+str(e), file=sys.stderr)
621 sys.exit(1)
622
623
624
625 yaml.add_constructor(u'!radians', construct_angle_radians)
626 yaml.add_constructor(u'!degrees', construct_angle_degrees)
627
628
629 pattern = re.compile(r'^deg\([^\)]*\)$')
630 yaml.add_implicit_resolver(u'!degrees', pattern, first="deg(")
631 pattern = re.compile(r'^rad\([^\)]*\)$')
632 yaml.add_implicit_resolver(u'!radians', pattern, first="rad(")
633