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