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  # Revision $Id: core.py 13228 2011-02-14 05:40:41Z kwc $ 
 34   
 35  """ 
 36  Core roslaunch model and lower-level utility routines. 
 37  """ 
 38   
 39  import os 
 40  import logging 
 41  import socket 
 42  import sys 
 43  import xmlrpclib 
 44   
 45   
 46  import roslib.names  
 47  import roslib.network 
 48  import roslib.substitution_args 
 49  import roslib.rosenv 
 50   
 51  #TODO:temporary until xacro is ported after next ROS stable release 
 52  resolve_args = roslib.substitution_args.resolve_args 
 53   
54 -class RLException(Exception):
55 """Base roslaunch exception type""" 56 pass
57 58 59 ## Phases allow executables to be assigned to a particular run period 60 PHASE_SETUP = 'setup' 61 PHASE_RUN = 'run' 62 PHASE_TEARDOWN = 'teardown' 63 64 _child_mode = False
65 -def is_child_mode():
66 """ 67 @return: True if roslaunch is running in remote child mode 68 @rtype: bool 69 """ 70 return _child_mode
71 -def set_child_mode(child_mode):
72 """ 73 @param child_mode: True if roslaunch is running in remote 74 child mode 75 @type child_mode: bool 76 """ 77 global _child_mode 78 _child_mode = child_mode
79
80 -def is_machine_local(machine):
81 """ 82 Check to see if machine is local. NOTE: a machine is not local if 83 its user credentials do not match the current user. 84 @param machine: Machine 85 @type machine: L{Machine} 86 @return: True if machine is local and doesn't require remote login 87 @rtype: bool 88 """ 89 try: 90 machine_addr = socket.gethostbyname(machine.address) 91 except socket.gaierror: 92 raise RLException("cannot resolve host address for machine [%s]"%machine.address) 93 local_addresses = ['localhost'] + roslib.network.get_local_addresses() 94 # check 127/8 and local addresses 95 is_local = machine_addr.startswith('127.') or machine_addr in local_addresses 96 97 #491: override local to be ssh if machine.user != local user 98 if is_local and machine.user: 99 import getpass 100 is_local = machine.user == getpass.getuser() 101 return is_local
102 103 _printlog_handlers = [] 104 _printerrlog_handlers = []
105 -def printlog(msg):
106 """ 107 Core utility for printing message to stdout as well as printlog handlers 108 @param msg: message to print 109 @type msg: str 110 """ 111 for h in _printlog_handlers: 112 try: # don't let this bomb out the actual code 113 h(msg) 114 except: 115 pass 116 try: # don't let this bomb out the actual code 117 print msg 118 except: 119 pass
120
121 -def printlog_bold(msg):
122 """ 123 Similar to L{printlog()}, but the message printed to screen is bolded for greater clarity 124 @param msg: message to print 125 @type msg: str 126 """ 127 for h in _printlog_handlers: 128 try: # don't let this bomb out the actual code 129 h(msg) 130 except: 131 pass 132 try: # don't let this bomb out the actual code 133 print '\033[1m%s\033[0m'%msg 134 except: 135 pass
136
137 -def printerrlog(msg):
138 """ 139 Core utility for printing message to stderr as well as printerrlog handlers 140 @param msg: message to print 141 @type msg: str 142 """ 143 for h in _printerrlog_handlers: 144 try: # don't let this bomb out the actual code 145 h(msg) 146 except: 147 pass 148 # #1003: this has raised IOError (errno 104) in robot use. Better to 149 # trap than let a debugging routine fault code. 150 try: # don't let this bomb out the actual code 151 print >> sys.stderr, '\033[31m%s\033[0m'%msg 152 except: 153 pass
154
155 -def add_printlog_handler(h):
156 """ 157 Register additional handler for printlog() 158 """ 159 _printlog_handlers.append(h)
160
161 -def add_printerrlog_handler(h):
162 """ 163 Register additional handler for printerrlog() 164 """ 165 _printerrlog_handlers.append(h)
166
167 -def clear_printlog_handlers():
168 """ 169 Delete all printlog handlers. required for testing 170 """ 171 del _printlog_handlers[:]
172
173 -def clear_printerrlog_handlers():
174 """ 175 Delete all printerrlog handlers. required for testing 176 """ 177 del _printerrlog_handlers[:]
178
179 -def setup_env(node, machine, master_uri):
180 """ 181 Create dictionary of environment variables to set for launched 182 process. 183 184 setup_env() will only set ROS_*, PYTHONPATH, and user-specified 185 environment variables. 186 187 @param machine Machine: machine being launched on 188 @type machine: L{Machine} 189 @param node: node that is being launched or None 190 @type node: L{Node} 191 @param master_uri: ROS master URI 192 @type master_uri: str 193 @return: process env dictionary 194 @rtype: dict 195 """ 196 d = {} 197 d[roslib.rosenv.ROS_MASTER_URI] = master_uri 198 d[roslib.rosenv.ROS_ROOT] = machine.ros_root or get_ros_root() 199 if machine.ros_package_path: #optional 200 d[roslib.rosenv.ROS_PACKAGE_PATH] = machine.ros_package_path 201 if machine.ros_ip: #optional 202 d[roslib.rosenv.ROS_IP] = machine.ros_ip 203 204 # roslib now depends on PYTHONPATH being set. This environment 205 # needs to be setup correctly for roslaunch through ssh to work 206 d['PYTHONPATH'] = os.path.join(d[roslib.rosenv.ROS_ROOT],'core','roslib', 'src') 207 208 # load in machine env_args. Node env args have precedence 209 for name, value in machine.env_args: 210 d[name] = value 211 212 # add node-specific env args last as they have highest precedence 213 if node: 214 ns = node.namespace 215 if ns[-1] == '/': 216 ns = ns[:-1] 217 if ns: 218 d[roslib.rosenv.ROS_NAMESPACE] = ns 219 for name, value in node.env_args: 220 d[name] = value 221 222 return d
223
224 -def rle_wrapper(fn):
225 """ 226 Wrap lower-level exceptions in RLException class 227 @return: function wrapper that throws an RLException if the 228 wrapped function throws an Exception 229 @rtype: fn 230 """ 231 def wrapped_fn(*args): 232 try: 233 return fn(*args) 234 except Exception, e: 235 # we specifically catch RLExceptions and print their messages differently 236 raise RLException("ERROR: %s"%e)
237 return wrapped_fn 238 239 get_ros_root = rle_wrapper(roslib.rosenv.get_ros_root) 240 get_master_uri_env = rle_wrapper(roslib.rosenv.get_master_uri)
241 -def get_ros_package_path():
242 """ 243 @return: ROS_PACKAGE_PATH value 244 @rtype: str 245 """ 246 # ROS_PACKAGE_PATH not required to be set 247 return roslib.rosenv.get_ros_package_path(required=False)
248
249 -def remap_localhost_uri(uri, force_localhost=False):
250 """ 251 Resolve localhost addresses to an IP address so that 252 @param uri: XML-RPC URI 253 @type uri: str 254 @param force_localhost: if True, URI is mapped onto the local machine no matter what 255 @type force_localhost: bool 256 """ 257 hostname, port = roslib.network.parse_http_host_and_port(uri) 258 if force_localhost or hostname == 'localhost': 259 return roslib.network.create_local_xmlrpc_uri(port) 260 else: 261 return uri
262 263 ################################################################## 264 # DATA STRUCTURES 265
266 -class Master:
267 """ 268 Data structure for representing and querying state of master 269 """ 270 __slots__ = ['type', 'auto', 'uri'] 271 ROSMASTER = 'rosmaster' 272 273 # deprecated 274 ZENMASTER = 'zenmaster' 275
276 - def __init__(self, type_=None, uri=None, auto=None):
277 """ 278 Create new Master instance. 279 @param uri: master URI. Defaults to ROS_MASTER_URI environment variable. 280 @type uri: str 281 @param type_: Currently only support 'rosmaster' 282 @type type_: str 283 """ 284 self.auto = None # no longer used 285 self.type = type_ or Master.ROSMASTER 286 self.uri = uri or get_master_uri_env()
287
288 - def get_host(self):
289 # parse from the URI 290 host, _ = roslib.network.parse_http_host_and_port(self.uri) 291 return host
292
293 - def get_port(self):
294 """ 295 Get the port this master is configured for. 296 """ 297 # parse from the URI 298 _, urlport = roslib.network.parse_http_host_and_port(self.uri) 299 return urlport
300
301 - def __eq__(self, m2):
302 if not isinstance(m2, Master): 303 return False 304 else: 305 return m2.type == self.type and m2.uri == self.uri
306
307 - def get(self):
308 """ 309 @return: XMLRPC proxy for communicating with master 310 @rtype: xmlrpclib.ServerProxy 311 """ 312 return xmlrpclib.ServerProxy(self.uri)
313
314 - def get_multi(self):
315 """ 316 @return: multicall XMLRPC proxy for communicating with master 317 @rtype: xmlrpclib.MultiCall 318 """ 319 return xmlrpclib.MultiCall(self.get())
320
321 - def is_running(self):
322 """ 323 Check if master is running. 324 @return: True if the master is running 325 @rtype: bool 326 """ 327 try: 328 try: 329 to_orig = socket.getdefaulttimeout() 330 # enable timeout 331 socket.setdefaulttimeout(5.0) 332 logging.getLogger('roslaunch').info('master.is_running[%s]'%self.uri) 333 code, status, val = self.get().getPid('/roslaunch') 334 if code != 1: 335 raise RLException("ERROR: master failed status check: %s"%msg) 336 logging.getLogger('roslaunch.core').debug('master.is_running[%s]: True'%self.uri) 337 return True 338 finally: 339 socket.setdefaulttimeout(to_orig) 340 except: 341 logging.getLogger('roslaunch.core').debug('master.is_running[%s]: True'%self.uri) 342 return False
343 344 ## number of seconds that a child machine is allowed to register with 345 ## the parent before being considered failed 346 _DEFAULT_REGISTER_TIMEOUT = 10.0 347
348 -class Machine(object):
349 """ 350 Data structure for storing information about a machine in the ROS 351 system. Corresponds to the 'machine' tag in the launch 352 specification. 353 """ 354 __slots__ = ['name', 'ros_root', 'ros_package_path', 'ros_ip',\ 355 'address', 'ssh_port', 'user', 'password', 'assignable',\ 356 'env_args', 'timeout']
357 - def __init__(self, name, ros_root, ros_package_path, \ 358 address, ros_ip=None, ssh_port=22, user=None, password=None, \ 359 assignable=True, env_args=[], timeout=None):
360 """ 361 @param name: machine name 362 @type name: str 363 @param ros_root: ROS_ROOT on machine 364 @type ros_root: str 365 @param ros_package_path: ROS_PACKAGE_PATH on machine 366 @type ros_package_path: str 367 @param address: network address of machine 368 @type address: str 369 @param ros_ip: ROS_IP on machine 370 @type ros_ip: str 371 @param ssh_port: SSH port number 372 @type ssh_port: int 373 @param user: SSH username 374 @type user: str 375 @param password: SSH password. Not recommended for use. Use SSH keys instead. 376 @type password: str 377 """ 378 self.name = name 379 self.ros_root = ros_root 380 self.ros_package_path = ros_package_path 381 self.ros_ip = ros_ip or None 382 self.user = user or None 383 self.password = password or None 384 self.address = address 385 self.ssh_port = ssh_port 386 self.assignable = assignable 387 self.env_args = env_args 388 self.timeout = timeout or _DEFAULT_REGISTER_TIMEOUT
389
390 - def __str__(self):
391 return "Machine(name[%s] ros_root[%s] ros_package_path[%s] ros_ip[%s] address[%s] ssh_port[%s] user[%s] assignable[%s] env_args[%s] timeout[%s])"%(self.name, self.ros_root, self.ros_package_path, self.ros_ip, self.address, self.ssh_port, self.user, self.assignable, str(self.env_args), self.timeout)
392 - def __eq__(self, m2):
393 if not isinstance(m2, Machine): 394 return False 395 return self.name == m2.name and \ 396 self.assignable == m2.assignable and \ 397 self.config_equals(m2)
398
399 - def config_key(self):
400 """ 401 Get a key that represents the configuration of the 402 machine. machines with identical configurations have identical 403 keys 404 405 @return: configuration key 406 @rtype: str 407 """ 408 return "Machine(address[%s] ros_root[%s] ros_package_path[%s] ros_ip[%s] ssh_port[%s] user[%s] password[%s] env_args[%s] timeout[%s])"%(self.address, self.ros_root, self.ros_package_path, self.ros_ip or '', self.ssh_port, self.user or '', self.password or '', str(self.env_args), self.timeout)
409
410 - def config_equals(self, m2):
411 """ 412 @return: True if machines have identical configurations 413 @rtype: bool 414 """ 415 if not isinstance(m2, Machine): 416 return False 417 return self.ros_root == m2.ros_root and \ 418 self.ros_package_path == m2.ros_package_path and \ 419 self.ros_ip == m2.ros_ip and \ 420 self.address == m2.address and \ 421 self.ssh_port == m2.ssh_port and \ 422 self.user == m2.user and \ 423 self.password == m2.password and \ 424 set(self.env_args) == set(m2.env_args) and \ 425 self.timeout == m2.timeout
426
427 - def __ne__(self, m2):
428 return not self.__eq__(m2)
429
430 -class Param(object):
431 """ 432 Data structure for storing information about a desired parameter in 433 the ROS system Corresponds to the 'param' tag in the launch 434 specification. 435 """
436 - def __init__(self, key, value):
437 self.key = roslib.names.canonicalize_name(key) 438 self.value = value
439 - def __eq__(self, p):
440 if not isinstance(p, Param): 441 return False 442 return p.key == self.key and p.value == self.value
443 - def __ne__(self, p):
444 return not self.__eq__(p)
445 - def __str__(self):
446 return "%s=%s"%(self.key, self.value)
447 - def __repr__(self):
448 return "%s=%s"%(self.key, self.value)
449 450 _local_m = None
451 -def local_machine():
452 """ 453 @return: Machine instance representing the local machine 454 @rtype: L{Machine} 455 """ 456 global _local_m 457 if _local_m is None: 458 _local_m = Machine('', get_ros_root(), \ 459 get_ros_package_path(), 'localhost',\ 460 ros_ip=roslib.network.get_address_override()) 461 return _local_m
462
463 -class Node(object):
464 """ 465 Data structure for storing information about a desired node in 466 the ROS system Corresponds to the 'node' tag in the launch 467 specification. 468 """ 469 __slots__ = ['package', 'type', 'name', 'namespace', \ 470 'machine_name', 'machine', 'args', 'respawn', \ 471 'remap_args', 'env_args',\ 472 'process_name', 'output', 'cwd', 473 'launch_prefix', 'required', 474 'filename'] 475
476 - def __init__(self, package, node_type, name=None, namespace='/', \ 477 machine_name=None, args='', respawn=False, \ 478 remap_args=None,env_args=None, output=None, cwd=None, \ 479 launch_prefix=None, required=False, filename='<unknown>'):
480 """ 481 @param package: node package name 482 @type package: str 483 @param node_type: node type 484 @type node_type: str 485 @param name: node name 486 @type name: str 487 @param namespace: namespace for node 488 @type namespace: str 489 @param machine_name: name of machine to run node on 490 @type machine_name: str 491 @param args: argument string to pass to node executable 492 @type args: str 493 @param respawn: if True, respawn node if it dies 494 @type respawn: bool 495 @param remap_args: list of [(from, to)] remapping arguments 496 @type remap_args: [(str, str)]: 497 @param env_args: list of [(key, value)] of 498 additional environment vars to set for node 499 @type env_args: [(str, str)] 500 @param output: where to log output to, either Node, 'screen' or 'log' 501 @type output: str 502 @param cwd: current working directory of node, either 'node', 'ROS_HOME' or 'ros-root'. Default: ROS_HOME 503 @type cwd: str 504 @param launch_prefix: launch command/arguments to prepend to node executable arguments 505 @type launch_prefix: str 506 @param required: node is required to stay running (launch fails if node dies) 507 @type required: bool 508 @param filename: name of file Node was parsed from 509 @type filename: str 510 511 @raise ValueError: if parameters do not validate 512 """ 513 514 self.package = package 515 self.type = node_type 516 self.name = name or None 517 self.namespace = roslib.names.make_global_ns(namespace or '/') 518 self.machine_name = machine_name or None 519 self.respawn = respawn 520 self.args = args or '' 521 self.remap_args = remap_args or [] 522 self.env_args = env_args or [] 523 self.output = output 524 self.cwd = cwd 525 if self.cwd == 'ros_home': # be lenient on case 526 self.cwd = 'ROS_HOME' 527 elif self.cwd == 'ros-root': 528 printerrlog("WARNING: 'ros-root' value for <node> 'cwd' attribute is deprecated.") 529 530 self.launch_prefix = launch_prefix or None 531 self.required = required 532 self.filename = filename 533 534 if self.respawn and self.required: 535 raise ValueError("respawn and required cannot both be set to true") 536 537 # validation 538 if self.name and roslib.names.SEP in self.name: # #1821, namespaces in nodes need to be banned 539 raise ValueError("node name cannot contain a namespace") 540 if not len(self.package.strip()): 541 raise ValueError("package must be non-empty") 542 if not len(self.type.strip()): 543 raise ValueError("type must be non-empty") 544 if not self.output in ['log', 'screen', None]: 545 raise ValueError("output must be one of 'log', 'screen'") 546 if not self.cwd in ['ROS_HOME', 'ros-root', 'node', None]: 547 raise ValueError("cwd must be one of 'ROS_HOME', 'ros-root', 'node'") 548 549 # Extra slots for assigning later 550 551 # slot to store the process name in so that we can query the 552 # associated process state 553 self.process_name = None 554 555 # machine is the assigned machine instance. should probably 556 # consider storing this elsewhere as it can be inconsistent 557 # with machine_name and is also a runtime, rather than 558 # configuration property 559 self.machine = None
560 561 562
563 - def xmltype(self):
564 return 'node'
565
566 - def xmlattrs(self):
567 name_str = cwd_str = respawn_str = None 568 if self.name: 569 name_str = self.name 570 if self.cwd: 571 cwd_str = self.cwd 572 573 return [ 574 ('pkg', self.package), 575 ('type', self.type), 576 ('machine', self.machine_name), 577 ('ns', self.namespace), 578 ('args', self.args), 579 ('output', self.output), 580 ('cwd', cwd_str), 581 ('respawn', self.respawn), #not valid on <test> 582 ('name', name_str), 583 ('launch-prefix', self.launch_prefix), 584 ('required', self.required), 585 ]
586 587 #TODO: unify with to_remote_xml using a filter_fn
588 - def to_xml(self):
589 """ 590 convert representation into XML representation. Currently cannot represent private parameters. 591 @return: XML representation for remote machine 592 @rtype: str 593 """ 594 t = self.xmltype() 595 attrs = [(a, v) for a, v in self.xmlattrs() if v != None] 596 xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs])) 597 xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args]) 598 xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args]) 599 xmlstr += "</%s>"%t 600 return xmlstr
601
602 - def to_remote_xml(self):
603 """ 604 convert representation into remote representation. Remote representation does 605 not include parameter settings or 'machine' attribute 606 @return: XML representation for remote machine 607 @rtype: str 608 """ 609 t = self.xmltype() 610 attrs = [(a, v) for a, v in self.xmlattrs() if v != None and a != 'machine'] 611 xmlstr = '<%s %s>\n'%(t, ' '.join(['%s="%s"'%(val[0], _xml_escape(val[1])) for val in attrs])) 612 xmlstr += ''.join([' <remap from="%s" to="%s" />\n'%tuple(r) for r in self.remap_args]) 613 xmlstr += ''.join([' <env name="%s" value="%s" />\n'%tuple(e) for e in self.env_args]) 614 xmlstr += "</%s>"%t 615 return xmlstr
616
617 -def _xml_escape(s):
618 """ 619 Escape string for XML 620 @param s: string to escape 621 @type s: str 622 @return: string with XML entities (<, >, ", &) escaped. 623 @rtype: str 624 """ 625 # gross, but doesn't need to be fast. always replace amp first 626 s = str(s) 627 s = s.replace('&', '&amp;') 628 s = s.replace('"', '&quot;') 629 s = s.replace('>', '&gt;') 630 s = s.replace('<', '&lt;') 631 return s
632 633 TEST_TIME_LIMIT_DEFAULT = 1 * 60 #seconds 634 635
636 -class Test(Node):
637 """ 638 A Test is a Node with special semantics that it performs a 639 unit/integration test. The data model is the same except the 640 option to set the respawn flag is removed. 641 """ 642 __slots__ = ['test_name', 'time_limit', 'retry'] 643
644 - def __init__(self, test_name, package, node_type, name=None, \ 645 namespace='/', machine_name=None, args='', \ 646 remap_args=None, env_args=None, time_limit=None, cwd=None, 647 launch_prefix=None, retry=None, filename="<unknown>"):
648 """ 649 Construct a new test node. 650 @param test_name: name of test for recording in test results 651 @type test_name: str 652 @param time_limit: number of seconds that a test 653 should run before marked as a failure 654 @type time_limit: int/float/long 655 """ 656 super(Test, self).__init__(package, node_type, name=name, \ 657 namespace=namespace, \ 658 machine_name=machine_name, args=args, \ 659 remap_args=remap_args, 660 env_args=env_args, 661 #output always is log 662 output='log', cwd=cwd, 663 launch_prefix=launch_prefix, filename=filename) 664 self.test_name = test_name 665 666 self.retry = retry or 0 667 time_limit = time_limit or TEST_TIME_LIMIT_DEFAULT 668 if not type(time_limit) in (float, int, long): 669 raise ValueError("'time-limit' must be a number") 670 time_limit = float(time_limit) #force to floating point 671 if time_limit <= 0: 672 raise ValueError("'time-limit' must be a positive number") 673 674 self.time_limit = time_limit
675
676 - def xmltype(self):
677 return 'test'
678
679 - def xmlattrs(self):
680 """ 681 NOTE: xmlattrs does not necessarily produce identical XML as 682 to what it was initialized with, though the properties are the same 683 """ 684 attrs = Node.xmlattrs(self) 685 attrs = [(a, v) for (a, v) in attrs if a != 'respawn'] 686 attrs.append(('test-name', self.test_name)) 687 688 if self.retry: 689 attrs.append(('retry', str(self.retry))) 690 if self.time_limit != TEST_TIME_LIMIT_DEFAULT: 691 attrs.append(('time-limit', self.time_limit)) 692 return attrs
693 694
695 -class Executable(object):
696 """ 697 Executable is a generic container for exectuable commands. 698 """ 699
700 - def __init__(self, cmd, args, phase=PHASE_RUN):
701 """ 702 @param cmd: name of command to run 703 @type cmd: str 704 @param args: arguments to command 705 @type args: (str,) 706 @param phase: PHASE_SETUP|PHASE_RUN|PHASE_TEARDOWN. Indicates whether the 707 command should be run before, during, or after launch. 708 @type phase: str 709 """ 710 self.command = cmd 711 self.args = args 712 self.phase = phase
713 - def __repr__(self):
714 return "%s %s"%(self.command, ' '.join(self.args))
715 - def __str__(self):
716 return "%s %s"%(self.command, ' '.join(self.args))
717
718 -class RosbinExecutable(Executable):
719 """ 720 RosbinExecutables are exectuables stored in ROS_ROOT/bin. 721 """
722 - def __init__(self, cmd, args, phase=PHASE_RUN):
723 super(RosbinExecutable, self).__init__(cmd, args, phase)
724 - def __repr__(self):
725 return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
726 - def __str__(self):
727 return "ros/bin/%s %s"%(self.command, ' '.join(self.args))
728 729
730 -def generate_run_id():
731 """ 732 Utility routine for generating run IDs (UUIDs) 733 @return: guid 734 @rtype: str 735 """ 736 import uuid 737 return str(uuid.uuid1())
738