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