Package roslaunch :: Module core
[frames] | no frames]

Source Code for Module roslaunch.core

  1  # Software License Agreement (BSD License) 
  2  # 
  3  # Copyright (c) 2008, Willow Garage, Inc. 
  4  # All rights reserved. 
  5  # 
  6  # Redistribution and use in source and binary forms, with or without 
  7  # modification, are permitted provided that the following conditions 
  8  # are met: 
  9  # 
 10  #  * Redistributions of source code must retain the above copyright 
 11  #    notice, this list of conditions and the following disclaimer. 
 12  #  * Redistributions in binary form must reproduce the above 
 13  #    copyright notice, this list of conditions and the following 
 14  #    disclaimer in the documentation and/or other materials provided 
 15  #    with the distribution. 
 16  #  * Neither the name of Willow Garage, Inc. nor the names of its 
 17  #    contributors may be used to endorse or promote products derived 
 18  #    from this software without specific prior written permission. 
 19  # 
 20  # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 
 21  # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 
 22  # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 
 23  # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 
 24  # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 
 25  # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 
 26  # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 
 27  # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 
 28  # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 
 29  # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 
 30  # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 
 31  # POSSIBILITY OF SUCH DAMAGE. 
 32   
 33  from __future__ import print_function 
 34   
 35  """ 
 36  Core roslaunch model and lower-level utility routines. 
 37  """ 
 38   
 39  import os 
 40  import logging 
 41   
 42  import socket 
 43  import sys 
 44  try: 
 45      from xmlrpc.client import MultiCall, ServerProxy 
 46  except ImportError: 
 47      from xmlrpclib import MultiCall, ServerProxy 
 48   
 49  import rospkg 
 50   
 51  import rosgraph 
 52  import rosgraph.names  
 53  import rosgraph.network 
 54   
 55  from xml.sax.saxutils import escape  
 56  try: 
 57      unicode 
 58  except NameError: 
 59      # Python 3: for _xml_escape 
 60      basestring = unicode = str 
 61       
62 -class RLException(Exception):
63 """Base roslaunch exception type""" 64 pass
65 66 ## Phases allow executables to be assigned to a particular run period 67 PHASE_SETUP = 'setup' 68 PHASE_RUN = 'run' 69 PHASE_TEARDOWN = 'teardown' 70 71 _child_mode = False
72 -def is_child_mode():
73 """ 74 :returns: ``True`` if roslaunch is running in remote child mode, ``bool`` 75 """ 76 return _child_mode
77 -def set_child_mode(child_mode):
78 """ 79 :param child_mode: True if roslaunch is running in remote 80 child mode, ``bool`` 81 """ 82 global _child_mode 83 _child_mode = child_mode
84
85 -def is_machine_local(machine):
86 """ 87 Check to see if machine is local. NOTE: a machine is not local if 88 its user credentials do not match the current user. 89 :param machine: Machine, ``Machine`` 90 :returns: True if machine is local and doesn't require remote login, ``bool`` 91 """ 92 try: 93 # If Python has ipv6 disabled but machine.address can be resolved somehow to an ipv6 address, then host[4][0] will be int 94 machine_ips = [host[4][0] for host in socket.getaddrinfo(machine.address, 0, 0, 0, socket.SOL_TCP) if isinstance(host[4][0], str)] 95 except socket.gaierror: 96 raise RLException("cannot resolve host address for machine [%s]"%machine.address) 97 local_addresses = ['localhost'] + rosgraph.network.get_local_addresses() 98 # check 127/8 and local addresses 99 is_local = ([ip for ip in machine_ips if (ip.startswith('127.') or ip == '::1')] != []) or (set(machine_ips) & set(local_addresses) != set()) 100 101 #491: override local to be ssh if machine.user != local user 102 if is_local and machine.user: 103 import getpass 104 is_local = machine.user == getpass.getuser() 105 return is_local
106 107 _printlog_handlers = [] 108 _printerrlog_handlers = []
109 -def printlog(msg):
110 """ 111 Core utility for printing message to stdout as well as printlog handlers 112 :param msg: message to print, ``str`` 113 """ 114 for h in _printlog_handlers: 115 try: # don't let this bomb out the actual code 116 h(msg) 117 except: 118 pass 119 try: # don't let this bomb out the actual code 120 print(msg) 121 except: 122 pass
123
124 -def printlog_bold(msg):
125 """ 126 Similar to L{printlog()}, but the message printed to screen is bolded for greater clarity 127 :param msg: message to print, ``str`` 128 """ 129 for h in _printlog_handlers: 130 try: # don't let this bomb out the actual code 131 h(msg) 132 except: 133 pass 134 try: # don't let this bomb out the actual code 135 if sys.platform in ['win32']: 136 print('%s' % msg) # windows console is terrifically boring 137 else: 138 print('\033[1m%s\033[0m' % msg) 139 except: 140 pass
141
142 -def printerrlog(msg):
143 """ 144 Core utility for printing message to stderr as well as printerrlog handlers 145 :param msg: message to print, ``str`` 146 """ 147 for h in _printerrlog_handlers: 148 try: # don't let this bomb out the actual code 149 h(msg) 150 except: 151 pass 152 # #1003: this has raised IOError (errno 104) in robot use. Better to 153 # trap than let a debugging routine fault code. 154 try: # don't let this bomb out the actual code 155 print('\033[31m%s\033[0m' % msg, file=sys.stderr) 156 except: 157 pass
158
159 -def add_printlog_handler(h):
160 """ 161 Register additional handler for printlog() 162 """ 163 _printlog_handlers.append(h)
164
165 -def add_printerrlog_handler(h):
166 """ 167 Register additional handler for printerrlog() 168 """ 169 _printerrlog_handlers.append(h)
170
171 -def clear_printlog_handlers():
172 """ 173 Delete all printlog handlers. required for testing 174 """ 175 del _printlog_handlers[:]
176
177 -def clear_printerrlog_handlers():
178 """ 179 Delete all printerrlog handlers. required for testing 180 """ 181 del _printerrlog_handlers[:]
182
183 -def setup_env(node, machine, master_uri, env=None):
184 """ 185 Create dictionary of environment variables to set for launched 186 process. 187 188 setup_env() will only set ROS_*, PYTHONPATH, and user-specified 189 environment variables. 190 191 :param machine: machine being launched on, ``Machine`` 192 :param node: node that is being launched or None, ``Node`` 193 :param master_uri: ROS master URI, ``str`` 194 :param env: base environment configuration, defaults to ``os.environ`` 195 :returns: process env dictionary, ``dict`` 196 """ 197 if env is None: 198 env = os.environ 199 200 d = env.copy() 201 d[rosgraph.ROS_MASTER_URI] = master_uri 202 203 # add node-specific env args last as they have highest precedence 204 if node: 205 if rosgraph.ROS_NAMESPACE in d: 206 del d[rosgraph.ROS_NAMESPACE] 207 ns = node.namespace 208 if ns[-1] == '/': 209 ns = ns[:-1] 210 if ns: 211 d[rosgraph.ROS_NAMESPACE] = str(ns) 212 for name, value in node.env_args: 213 d[str(name)] = str(value) 214 215 return d
216
217 -def rle_wrapper(fn):
218 """ 219 Wrap lower-level exceptions in RLException class 220 :returns:: function wrapper that throws an RLException if the 221 wrapped function throws an Exception, ``fn`` 222 """ 223 def wrapped_fn(*args): 224 try: 225 return fn(*args) 226 except Exception as e: 227 # we specifically catch RLExceptions and print their messages differently 228 raise RLException("ERROR: %s"%e)
229 return wrapped_fn 230 231 get_ros_root = rospkg.get_ros_root 232 get_master_uri_env = rle_wrapper(rosgraph.get_master_uri) 233 get_ros_package_path = rospkg.get_ros_package_path 234
235 -def remap_localhost_uri(uri, force_localhost=False):
236 """ 237 Resolve localhost addresses to an IP address so that 238 :param uri: XML-RPC URI, ``str`` 239 :param force_localhost: if True, URI is mapped onto the local machine no matter what, ``bool`` 240 """ 241 hostname, port = rosgraph.network.parse_http_host_and_port(uri) 242 if force_localhost or hostname == 'localhost': 243 return rosgraph.network.create_local_xmlrpc_uri(port) 244 else: 245 return uri
246 247 ################################################################## 248 # DATA STRUCTURES 249
250 -class Master(object):
251 """ 252 Data structure for representing and querying state of master 253 """ 254 __slots__ = ['type', 'auto', 'uri'] 255 ROSMASTER = 'rosmaster' 256 257 # deprecated 258 ZENMASTER = 'zenmaster' 259
260 - def __init__(self, type_=None, uri=None, auto=None):
261 """ 262 Create new Master instance. 263 :param uri: master URI. Defaults to ROS_MASTER_URI environment variable, ``str`` 264 :param type_: Currently only support 'rosmaster', ``str`` 265 """ 266 self.auto = None # no longer used 267 self.type = type_ or Master.ROSMASTER 268 self.uri = uri or get_master_uri_env()
269
270 - def get_host(self):
271 # parse from the URI 272 host, _ = rosgraph.network.parse_http_host_and_port(self.uri) 273 return host
274
275 - def get_port(self):
276 """ 277 Get the port this master is configured for. 278 """ 279 # parse from the URI 280 _, urlport = rosgraph.network.parse_http_host_and_port(self.uri) 281 return urlport
282
283 - def __eq__(self, m2):
284 if not isinstance(m2, Master): 285 return False 286 else: 287 return m2.type == self.type and m2.uri == self.uri
288
289 - def get(self):
290 """ 291 :returns:: XMLRPC proxy for communicating with master, ``xmlrpc.client.ServerProxy`` 292 """ 293 return ServerProxy(self.uri)
294
295 - def get_multi(self):
296 """ 297 :returns:: multicall XMLRPC proxy for communicating with master, ``xmlrpc.client.MultiCall`` 298 """ 299 return MultiCall(self.get())
300
301 - def is_running(self):
302 """ 303 Check if master is running. 304 :returns:: True if the master is running, ``bool`` 305 """ 306 try: 307 try: 308 to_orig = socket.getdefaulttimeout() 309 # enable timeout 310 socket.setdefaulttimeout(5.0) 311 logging.getLogger('roslaunch').info('master.is_running[%s]'%self.uri) 312 code, status, val = self.get().getPid('/roslaunch') 313 if code != 1: 314 raise RLException("ERROR: master failed status check: %s"%msg) 315 logging.getLogger('roslaunch.core').debug('master.is_running[%s]: True'%self.uri) 316 return True 317 finally: 318 socket.setdefaulttimeout(to_orig) 319 except: 320 logging.getLogger('roslaunch.core').debug('master.is_running[%s]: False'%self.uri) 321 return False
322 323 ## number of seconds that a child machine is allowed to register with 324 ## the parent before being considered failed 325 _DEFAULT_REGISTER_TIMEOUT = 10.0 326
327 -class Machine(object):
328 """ 329 Data structure for storing information about a machine in the ROS 330 system. Corresponds to the 'machine' tag in the launch 331 specification. 332 """ 333 __slots__ = ['name', 'address', 'ssh_port', 'user', 'password', 'assignable', 334 'env_loader', 'timeout']
335 - def __init__(self, name, address, 336 env_loader=None, ssh_port=22, user=None, password=None, 337 assignable=True, env_args=[], timeout=None):
338 """ 339 :param name: machine name, ``str`` 340 :param address: network address of machine, ``str`` 341 :param env_loader: Path to environment loader, ``str`` 342 :param ssh_port: SSH port number, ``int`` 343 :param user: SSH username, ``str`` 344 :param password: SSH password. Not recommended for use. Use SSH keys instead., ``str`` 345 """ 346 self.name = name 347 self.env_loader = env_loader 348 self.user = user or None 349 self.password = password 350 self.address = address 351 self.ssh_port = ssh_port 352 self.assignable = assignable 353 self.timeout = timeout or _DEFAULT_REGISTER_TIMEOUT
354
355 - def __str__(self):
356 return "Machine(name[%s] env_loader[%s] address[%s] ssh_port[%s] user[%s] assignable[%s] timeout[%s])"%(self.name, self.env_loader, self.address, self.ssh_port, self.user, self.assignable, self.timeout)
357 - def __eq__(self, m2):
358 if not isinstance(m2, Machine): 359 return False 360 return self.name == m2.name and \ 361 self.assignable == m2.assignable and \ 362 self.config_equals(m2)
363
364 - def config_key(self):
365 """ 366 Get a key that represents the configuration of the 367 machine. machines with identical configurations have identical 368 keys 369 370 :returns:: configuration key, ``str`` 371 """ 372 return "Machine(address[%s] env_loader[%s] ssh_port[%s] user[%s] password[%s] timeout[%s])"%(self.address, self.env_loader, self.ssh_port, self.user or '', self.password or '', self.timeout)
373
374 - def config_equals(self, m2):
375 """ 376 :returns:: True if machines have identical configurations, ``bool`` 377 """ 378 if not isinstance(m2, Machine): 379 return False 380 return self.config_key() == m2.config_key()
381
382 - def __ne__(self, m2):
383 return not self.__eq__(m2)
384
385 -class Param(object):
386 """ 387 Data structure for storing information about a desired parameter in 388 the ROS system Corresponds to the 'param' tag in the launch 389 specification. 390 """
391 - def __init__(self, key, value):
392 self.key = rosgraph.names.canonicalize_name(key) 393 self.value = value
394 - def __eq__(self, p):
395 if not isinstance(p, Param): 396 return False 397 return p.key == self.key and p.value == self.value
398 - def __ne__(self, p):
399 return not self.__eq__(p)
400 - def __str__(self):
401 return "%s=%s"%(self.key, self.value)
402 - def __repr__(self):
403 return "%s=%s"%(self.key, self.value)
404 405 _local_m = None
406 -def local_machine():
407 """ 408 :returns:: Machine instance representing the local machine, ``Machine`` 409 """ 410 global _local_m 411 if _local_m is None: 412 _local_m = Machine('', 'localhost') 413 return _local_m
414
415 -class Node(object):
416 """ 417 Data structure for storing information about a desired node in 418 the ROS system Corresponds to the 'node' tag in the launch 419 specification. 420 """ 421 __slots__ = ['package', 'type', 'name', 'namespace', \ 422 'machine_name', 'machine', 'args', 'respawn', \ 423 'respawn_delay', \ 424 'remap_args', 'env_args',\ 425 'process_name', 'output', 'cwd', 426 'launch_prefix', 'required', 427 'filename'] 428
429 - def __init__(self, package, node_type, name=None, namespace='/', \ 430 machine_name=None, args='', \ 431 respawn=False, respawn_delay=0.0, \ 432 remap_args=None,env_args=None, output=None, cwd=None, \ 433 launch_prefix=None, required=False, filename='<unknown>'):
434 """ 435 :param package: node package name, ``str`` 436 :param node_type: node type, ``str`` 437 :param name: node name, ``str`` 438 :param namespace: namespace for node, ``str`` 439 :param machine_name: name of machine to run node on, ``str`` 440 :param args: argument string to pass to node executable, ``str`` 441 :param respawn: if True, respawn node if it dies, ``bool`` 442 :param respawn: if respawn is True, respawn node after delay, ``float`` 443 :param remap_args: list of [(from, to)] remapping arguments, ``[(str, str)]`` 444 :param env_args: list of [(key, value)] of 445 additional environment vars to set for node, ``[(str, str)]`` 446 :param output: where to log output to, either Node, 'screen' or 'log', ``str`` 447 :param cwd: current working directory of node, either 'node', 'ROS_HOME'. Default: ROS_HOME, ``str`` 448 :param launch_prefix: launch command/arguments to prepend to node executable arguments, ``str`` 449 :param required: node is required to stay running (launch fails if node dies), ``bool`` 450 :param filename: name of file Node was parsed from, ``str`` 451 452 :raises: :exc:`ValueError` If parameters do not validate 453 """ 454 455 self.package = package 456 self.type = node_type 457 self.name = name or None 458 self.namespace = rosgraph.names.make_global_ns(namespace or '/') 459 self.machine_name = machine_name or None 460 self.respawn = respawn 461 self.respawn_delay = respawn_delay 462 self.args = args or '' 463 self.remap_args = remap_args or [] 464 self.env_args = env_args or [] 465 self.output = output 466 self.cwd = cwd 467 if self.cwd == 'ros_home': # be lenient on case 468 self.cwd = 'ROS_HOME' 469 470 self.launch_prefix = launch_prefix or None 471 self.required = required 472 self.filename = filename 473 474 if self.respawn and self.required: 475 raise ValueError("respawn and required cannot both be set to true") 476 477 # validation 478 if self.name and rosgraph.names.SEP in self.name: # #1821, namespaces in nodes need to be banned 479 raise ValueError("node name cannot contain a namespace") 480 if not len(self.package.strip()): 481 raise ValueError("package must be non-empty") 482 if not len(self.type.strip()): 483 raise ValueError("type must be non-empty") 484 if not self.output in ['log', 'screen', None]: 485 raise ValueError("output must be one of 'log', 'screen'") 486 if not self.cwd in ['ROS_HOME', 'node', None]: 487 raise ValueError("cwd must be one of 'ROS_HOME', 'node'") 488 489 # Extra slots for assigning later 490 491 # slot to store the process name in so that we can query the 492 # associated process state 493 self.process_name = None 494 495 # machine is the assigned machine instance. should probably 496 # consider storing this elsewhere as it can be inconsistent 497 # with machine_name and is also a runtime, rather than 498 # configuration property 499 self.machine = None
500 501 502
503 - def xmltype(self):
504 return 'node'
505
506 - def xmlattrs(self):
507 name_str = cwd_str = respawn_str = None 508 if self.name: 509 name_str = self.name 510 if self.cwd: 511 cwd_str = self.cwd 512 513 return [ 514 ('pkg', self.package), 515 ('type', self.type), 516 ('machine', self.machine_name), 517 ('ns', self.namespace), 518 ('args', self.args), 519 ('output', self.output), 520 ('cwd', cwd_str), 521 ('respawn', self.respawn), #not valid on <test> 522 ('respawn_delay', self.respawn_delay), # not valid on <test> 523 ('name', name_str), 524 ('launch-prefix', self.launch_prefix), 525 ('required', self.required), 526 ]
527 528 #TODO: unify with to_remote_xml using a filter_fn
529 - def to_xml(self):
530 """ 531 convert representation into XML representation. Currently cannot represent private parameters. 532 :returns:: XML representation for remote machine, ``str`` 533 """ 534 t = self.xmltype() 535 attrs = [(a, v) for a, v in self.xmlattrs() if v != None] 536 xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs])) 537 xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args]) 538 xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args]) 539 xmlstr += "</%s>"%t 540 return xmlstr
541
542 - def to_remote_xml(self):
543 """ 544 convert representation into remote representation. Remote representation does 545 not include parameter settings or 'machine' attribute 546 :returns:: XML representation for remote machine, ``str`` 547 """ 548 t = self.xmltype() 549 attrs = [(a, v) for a, v in self.xmlattrs() if v != None and a != 'machine'] 550 xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs])) 551 xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args]) 552 xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args]) 553 xmlstr += "</%s>"%t 554 return xmlstr
555
556 -def _xml_escape(s):
557 """ 558 Escape string for XML 559 :param s: string to escape, ``str`` 560 :returns:: string with XML entities (<, >, \", &) escaped, ``str`` 561 """ 562 # use official escaping to preserve unicode. 563 # see import at the top for py3k-compat 564 if isinstance(s, basestring): 565 return escape(s, entities={'"': '&quot;'}) 566 else: 567 # don't escape non-string attributes 568 return s
569 570 TEST_TIME_LIMIT_DEFAULT = 1 * 60 #seconds 571 572
573 -class Test(Node):
574 """ 575 A Test is a Node with special semantics that it performs a 576 unit/integration test. The data model is the same except the 577 option to set the respawn flag is removed. 578 """ 579 __slots__ = ['test_name', 'time_limit', 'retry'] 580
581 - def __init__(self, test_name, package, node_type, name=None, \ 582 namespace='/', machine_name=None, args='', \ 583 remap_args=None, env_args=None, time_limit=None, cwd=None, 584 launch_prefix=None, retry=None, filename="<unknown>"):
585 """ 586 Construct a new test node. 587 :param test_name: name of test for recording in test results, ``str`` 588 :param time_limit: number of seconds that a test 589 should run before marked as a failure, ``int/float/long`` 590 """ 591 super(Test, self).__init__(package, node_type, name=name, \ 592 namespace=namespace, \ 593 machine_name=machine_name, args=args, \ 594 remap_args=remap_args, 595 env_args=env_args, 596 #output always is log 597 output='log', cwd=cwd, 598 launch_prefix=launch_prefix, filename=filename) 599 self.test_name = test_name 600 601 self.retry = retry or 0 602 time_limit = time_limit or TEST_TIME_LIMIT_DEFAULT 603 number_types = [float, int] 604 try: 605 number_types.append(long) 606 except NameError: 607 pass 608 if not type(time_limit) in number_types: 609 raise ValueError("'time-limit' must be a number") 610 time_limit = float(time_limit) #force to floating point 611 if time_limit <= 0: 612 raise ValueError("'time-limit' must be a positive number") 613 614 self.time_limit = time_limit
615
616 - def xmltype(self):
617 return 'test'
618
619 - def xmlattrs(self):
620 """ 621 NOTE: xmlattrs does not necessarily produce identical XML as 622 to what it was initialized with, though the properties are the same 623 """ 624 attrs = Node.xmlattrs(self) 625 attrs = [(a, v) for (a, v) in attrs if a not in ['respawn', \ 626 'respawn_delay']] 627 attrs.append(('test-name', self.test_name)) 628 629 if self.retry: 630 attrs.append(('retry', str(self.retry))) 631 if self.time_limit != TEST_TIME_LIMIT_DEFAULT: 632 attrs.append(('time-limit', self.time_limit)) 633 return attrs
634 635
636 -class Executable(object):
637 """ 638 Executable is a generic container for exectuable commands. 639 """ 640
641 - def __init__(self, cmd, args, phase=PHASE_RUN):
642 """ 643 :param cmd: name of command to run, ``str`` 644 :param args: arguments to command, ``(str,)`` 645 :param phase: PHASE_SETUP|PHASE_RUN|PHASE_TEARDOWN. Indicates whether the 646 command should be run before, during, or after launch, ``str`` 647 """ 648 self.command = cmd 649 self.args = args 650 self.phase = phase
651 - def __repr__(self):
652 return "%s %s"%(self.command, ' '.join(self.args))
653 - def __str__(self):
654 return "%s %s"%(self.command, ' '.join(self.args))
655
656 -class RosbinExecutable(Executable):
657 """ 658 RosbinExecutables are exectuables stored in ROS_ROOT/bin. 659 """
660 - def __init__(self, cmd, args, phase=PHASE_RUN):
661 super(RosbinExecutable, self).__init__(cmd, args, phase)
662 - def __repr__(self):
663 return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
664 - def __str__(self):
665 return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
666 667
668 -def generate_run_id():
669 """ 670 Utility routine for generating run IDs (UUIDs) 671 :returns: guid, ``str`` 672 """ 673 import uuid 674 return str(uuid.uuid1())
675