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