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

Source Code for Module roslaunch.launch

  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: launch.py 13228 2011-02-14 05:40:41Z kwc $ 
 34   
 35  """ 
 36  Top-level implementation of launching processes. Coordinates 
 37  lower-level libraries. 
 38  """ 
 39   
 40  import os 
 41  import logging 
 42  import sys 
 43  import time 
 44   
 45  import roslib.names 
 46  import roslib.network  
 47   
 48  from roslaunch.core import * 
 49  from roslaunch.config import ROSLaunchConfig 
 50  from roslaunch.nodeprocess import create_master_process, create_node_process 
 51  from roslaunch.pmon import start_process_monitor, ProcessListener, FatalProcessLaunch 
 52   
 53  from roslaunch.rlutil import update_terminal_name 
 54   
 55  _TIMEOUT_MASTER_START = 10.0 #seconds 
 56  _TIMEOUT_MASTER_STOP  = 10.0 #seconds 
 57   
 58  _ID = '/roslaunch' 
 59   
60 -class RLTestTimeoutException(RLException): pass
61
62 -def validate_master_launch(m, is_core):
63 """ 64 Validate the configuration of a master we are about to launch. Ths 65 validation already assumes that no existing master is running at 66 this configuration and merely checks configuration for a new 67 launch. 68 """ 69 # Before starting a master, we do some sanity check on the 70 # master configuration. There are two ways the user starts: 71 # roscore or roslaunch. If the user types roscore, we always 72 # will start a core if possible, but we warn about potential 73 # misconfigurations. If the user types roslaunch, we will 74 # auto-start a new master if it is achievable, i.e. if the 75 # master is local. 76 if not roslib.network.is_local_address(m.get_host()): 77 # The network configuration says that the intended 78 # hostname is not local, so... 79 if is_core: 80 # ...user is expecting to start a new master. Thus, we 81 # only warn if network configuration appears 82 # non-local. 83 try: 84 reverse_ip = socket.gethostbyname(m.get_host()) 85 local_addrs = roslib.network.get_local_addresses() 86 printerrlog("""WARNING: IP address %s for local hostname '%s' does not appear to match 87 any local IP address (%s). Your ROS nodes may fail to communicate. 88 89 Please use ROS_IP to set the correct IP address to use."""%(reverse_ip, m.get_host(), ','.join(local_addrs))) 90 except: 91 printerrlog("""WARNING: local hostname '%s' does not map to an IP address. 92 Your ROS nodes may fail to communicate. 93 94 Please use ROS_IP to set the correct IP address to use."""%(m.get_host())) 95 96 else: 97 # ... the remote master cannot be contacted, so we fail. #3097 98 raise RLException("ERROR: unable to contact ROS master at [%s]"%(m.uri)) 99 100 if is_core: 101 # User wants to start a master, and our configuration does 102 # point to the local host. 103 env_uri = roslib.rosenv.get_master_uri() 104 env_host, env_port = roslib.network.parse_http_host_and_port(env_uri) 105 106 if not roslib.network.is_local_address(env_host): 107 # The ROS_MASTER_URI points to a different machine, warn user 108 printerrlog("WARNING: ROS_MASTER_URI [%s] host is not set to this machine"%(env_uri)) 109 elif env_port != m.get_port(): 110 # The ROS_MASTER_URI points to a master on a different port, warn user 111 printerrlog("WARNING: ROS_MASTER_URI port [%s] does not match this roscore [%s]"%(env_port, m.get_port()))
112
113 -def _all_namespace_parents(p):
114 splits = [s for s in p.split(roslib.names.SEP) if s] 115 curr =roslib.names.SEP 116 parents = [curr] 117 for s in splits[:-1]: 118 next_ = curr + s + roslib.names.SEP 119 parents.append(next_) 120 curr = next_ 121 return parents
122
123 -def _unify_clear_params(params):
124 """ 125 Reduce clear_params such that only the highest-level namespaces 126 are represented for overlapping namespaces. e.g. if both /foo/ and 127 /foo/bar are present, return just /foo/. 128 129 @param params: paremter namees 130 @type params: [str] 131 @return: unified parameters 132 @rtype: [str] 133 """ 134 # note: this is a quick-and-dirty implementation 135 136 # canonicalize parameters 137 canon_params = [] 138 for p in params: 139 if not p[-1] == roslib.names.SEP: 140 p += roslib.names.SEP 141 if not p in canon_params: 142 canon_params.append(p) 143 # reduce operation 144 clear_params = canon_params[:] 145 for p in canon_params: 146 for parent in _all_namespace_parents(p): 147 if parent in canon_params and p in clear_params and p != '/': 148 clear_params.remove(p) 149 return clear_params
150
151 -def _hostname_to_rosname(hostname):
152 """ 153 Utility function to strip illegal characters from hostname. This 154 is implemented to be correct, not efficient.""" 155 156 # prepend 'host_', which guarantees leading alpha character 157 fixed = 'host_' 158 # simplify comparison by making name lowercase 159 hostname = hostname.lower() 160 for c in hostname: 161 # only allow alphanumeric and numeral 162 if (c >= 'a' and c <= 'z') or \ 163 (c >= '0' and c <= '9'): 164 fixed+=c 165 else: 166 fixed+='_' 167 return fixed
168
169 -class _ROSLaunchListeners(ProcessListener):
170 """ 171 Helper class to manage distributing process events. It functions as 172 a higher level aggregator of events. In particular, events about 173 remote and local processes require different mechanisms for being 174 caught and reported. 175 """
176 - def __init__(self):
177 self.process_listeners = []
178
179 - def add_process_listener(self, l):
180 """ 181 Add listener to list of listeners. Not threadsafe. 182 @param l: listener 183 @type l: L{ProcessListener} 184 """ 185 self.process_listeners.append(l)
186
187 - def process_died(self, process_name, exit_code):
188 """ 189 ProcessListener callback 190 """ 191 for l in self.process_listeners: 192 try: 193 l.process_died(process_name, exit_code) 194 except Exception, e: 195 import traceback 196 logging.getLogger('roslaunch').error(traceback.format_exc())
197
198 -class ROSLaunchListener(object):
199 """ 200 Listener interface for events related to ROSLaunch. 201 ROSLaunchListener is currently identical to the lower-level 202 L{roslaunch.pmon.ProcessListener} interface, but is separate for 203 architectural reasons. The lower-level 204 L{roslaunch.pmon.ProcessMonitor} does not provide events about 205 remotely running processes. 206 """ 207
208 - def process_died(self, process_name, exit_code):
209 """ 210 Notifies listener that process has died. This callback only 211 occurs for processes that die during normal process monitor 212 execution -- processes that are forcibly killed during 213 L{roslaunch.pmon.ProcessMonitor} shutdown are not reported. 214 @param process_name: name of process 215 @type process_name: str 216 @param exit_code int: exit code of process. If None, it means 217 that L{roslaunch.pmon.ProcessMonitor} was unable to determine an exit code. 218 @type exit_code: int 219 """ 220 pass
221
222 -class ROSLaunchRunner(object):
223 """ 224 Runs a roslaunch. The normal sequence of API calls is L{launch()} 225 followed by L{spin()}. An external thread can call L{stop()}; otherwise 226 the runner will block until an exit signal. Another usage is to 227 call L{launch()} followed by repeated calls to L{spin_once()}. This usage 228 allows the main thread to continue to do work while processes are 229 monitored. 230 """ 231
232 - def __init__(self, run_id, config, server_uri=None, pmon=None, is_core=False, remote_runner=None, is_child=False):
233 """ 234 @param run_id: /run_id for this launch. If the core is not 235 running, this value will be used to initialize /run_id. If 236 the core is already running, this value will be checked 237 against the value stored on the core. L{ROSLaunchRunner} will 238 fail during L{launch()} if they do not match. 239 @type run_id: str 240 @param config: roslauch instance to run 241 @type config: L{ROSLaunchConfig} 242 @param server_uri: XML-RPC URI of roslaunch server. 243 @type server_uri: str 244 @param pmon: optionally override the process 245 monitor the runner uses for starting and tracking processes 246 @type pmon: L{ProcessMonitor} 247 248 @param is_core: if True, this runner is a roscore 249 instance. This affects the error behavior if a master is 250 already running -- aborts if is_core is True and a core is 251 detected. 252 @type is_core: bool 253 @param remote_runner: remote roslaunch process runner 254 """ 255 if run_id is None: 256 raise RLException("run_id is None") 257 self.run_id = run_id 258 259 # In the future we should can separate the notion of a core 260 # config vs. the config being launched. In that way, we can 261 # start to migrate to a model where a config is a parameter to 262 # a launch() method, rather than a central thing to the 263 # runner. 264 self.config = config 265 self.server_uri = server_uri 266 self.is_child = is_child 267 self.is_core = is_core 268 self.logger = logging.getLogger('roslaunch') 269 self.pm = pmon or start_process_monitor() 270 271 # wire in ProcessMonitor events to our listeners 272 # aggregator. We similarly wire in the remote events when we 273 # create the remote runner. 274 self.listeners = _ROSLaunchListeners() 275 if self.pm is None: 276 raise RLException("unable to initialize roslaunch process monitor") 277 if self.pm.is_shutdown: 278 raise RLException("bad roslaunch process monitor initialization: process monitor is already dead") 279 280 self.pm.add_process_listener(self.listeners) 281 282 self.remote_runner = remote_runner
283
284 - def add_process_listener(self, l):
285 """ 286 Add listener to list of listeners. Not threadsafe. Must be 287 called before processes started. 288 @param l: listener 289 @type l: L{ProcessListener} 290 """ 291 self.listeners.add_process_listener(l)
292
293 - def _load_parameters(self):
294 """ 295 Load parameters onto the parameter server 296 """ 297 self.logger.info("load_parameters starting ...") 298 config = self.config 299 param_server = config.master.get() 300 p = None 301 try: 302 # multi-call style xmlrpc 303 param_server_multi = config.master.get_multi() 304 305 # clear specified parameter namespaces 306 # #2468 unify clear params to prevent error 307 for p in _unify_clear_params(config.clear_params): 308 if param_server.hasParam(_ID, p)[2]: 309 #printlog("deleting parameter [%s]"%p) 310 param_server_multi.deleteParam(_ID, p) 311 r = param_server_multi() 312 for code, msg, _ in r: 313 if code != 1: 314 raise RLException("Failed to clear parameter: %s"%(msg)) 315 316 # multi-call objects are not reusable 317 param_server_multi = config.master.get_multi() 318 for p in config.params.itervalues(): 319 # suppressing this as it causes too much spam 320 #printlog("setting parameter [%s]"%p.key) 321 param_server_multi.setParam(_ID, p.key, p.value) 322 r = param_server_multi() 323 for code, msg, _ in r: 324 if code != 1: 325 raise RLException("Failed to set parameter: %s"%(msg)) 326 except RLException: 327 raise 328 except Exception, e: 329 printerrlog("load_parameters: unable to set parameters (last param was [%s]): %s"%(p,e)) 330 raise #re-raise as this is fatal 331 self.logger.info("... load_parameters complete")
332
333 - def _launch_nodes(self):
334 """ 335 Launch all the declared nodes/master 336 @return: two lists of node names where the first 337 is the nodes that successfully launched and the second is the 338 nodes that failed to launch. 339 @rtype: [[str], [str]] 340 """ 341 config = self.config 342 succeeded = [] 343 failed = [] 344 self.logger.info("launch_nodes: launching local nodes ...") 345 local_nodes = config.nodes 346 347 # don't launch remote nodes 348 local_nodes = [n for n in config.nodes if is_machine_local(n.machine)] 349 350 for node in local_nodes: 351 proc, success = self.launch_node(node) 352 if success: 353 succeeded.append(str(proc)) 354 else: 355 failed.append(str(proc)) 356 357 if self.remote_runner: 358 self.logger.info("launch_nodes: launching remote nodes ...") 359 r_succ, r_fail = self.remote_runner.launch_remote_nodes() 360 succeeded.extend(r_succ) 361 failed.extend(r_fail) 362 363 self.logger.info("... launch_nodes complete") 364 return succeeded, failed
365
366 - def _launch_master(self):
367 """ 368 Launches master if requested. 369 @raise RLException: if master launch fails 370 """ 371 m = self.config.master 372 is_running = m.is_running() 373 374 if self.is_core and is_running: 375 raise RLException("roscore cannot run as another roscore/master is already running. \nPlease kill other roscore/master processes before relaunching.\nThe ROS_MASTER_URI is %s"%(m.uri)) 376 377 if not is_running: 378 validate_master_launch(m, self.is_core) 379 380 printlog("auto-starting new master") 381 p = create_master_process(self.run_id, m.type, get_ros_root(), m.get_port()) 382 self.pm.register_core_proc(p) 383 success = p.start() 384 if not success: 385 raise RLException("ERROR: unable to auto-start master process") 386 timeout_t = time.time() + _TIMEOUT_MASTER_START 387 while not m.is_running() and time.time() < timeout_t: 388 time.sleep(0.1) 389 390 if not m.is_running(): 391 raise RLException("ERROR: could not contact master [%s]"%m.uri) 392 393 printlog_bold("ROS_MASTER_URI=%s"%m.uri) 394 # TODO: although this dependency doesn't cause anything bad, 395 # it's still odd for launch to know about console stuff. This 396 # really should be an event. 397 update_terminal_name(m.uri) 398 399 # Param Server config params 400 param_server = m.get() 401 402 # #773: unique run ID 403 self._check_and_set_run_id(param_server, self.run_id) 404 405 if self.server_uri: 406 # store parent XML-RPC URI on param server 407 # - param name is the /roslaunch/hostname:port so that multiple roslaunches can store at once 408 hostname, port = roslib.network.parse_http_host_and_port(self.server_uri) 409 hostname = _hostname_to_rosname(hostname) 410 self.logger.info("setting /roslaunch/uris/%s__%s' to %s"%(hostname, port, self.server_uri)) 411 param_server.setParam(_ID, '/roslaunch/uris/%s__%s'%(hostname, port),self.server_uri)
412
413 - def _check_and_set_run_id(self, param_server, run_id):
414 """ 415 Initialize self.run_id to existing value or setup parameter 416 server with /run_id set to default_run_id 417 @param default_run_id: run_id to use if value is not set 418 @type default_run_id: str 419 @param param_server: parameter server proxy 420 @type param_server: xmlrpclib.ServerProxy 421 """ 422 code, _, val = param_server.hasParam(_ID, '/run_id') 423 if code == 1 and not val: 424 printlog_bold("setting /run_id to %s"%run_id) 425 param_server.setParam('/roslaunch', '/run_id', run_id) 426 else: 427 # verify that the run_id we have been set to matches what's on the parameter server 428 code, _, val = param_server.getParam('/roslaunch', '/run_id') 429 if code != 1: 430 #could only happen in a bad race condition with 431 #someone else restarting core 432 raise RLException("ERROR: unable to retrieve /run_id from parameter server") 433 if run_id != val: 434 raise RLException("run_id on parameter server does not match declared run_id: %s vs %s"%(val, run_id))
435 #self.run_id = val 436 #printlog_bold("/run_id is %s"%self.run_id) 437
438 - def _launch_executable(self, e):
439 """ 440 Launch a single L{Executable} object. Blocks until executable finishes. 441 @param e: Executable 442 @type e: L{Executable} 443 @raise RLException: if exectuable fails. Failure includes non-zero exit code. 444 """ 445 try: 446 #kwc: I'm still debating whether shell=True is proper 447 cmd = e.command 448 if isinstance(e, RosbinExecutable): 449 cmd = os.path.join(get_ros_root(), 'bin', cmd) 450 cmd = "%s %s"%(cmd, ' '.join(e.args)) 451 print "running %s"%cmd 452 local_machine = self.config.machines[''] 453 import roslaunch.node_args 454 env = roslaunch.node_args.create_local_process_env(None, local_machine, self.config.master.uri) 455 import subprocess 456 retcode = subprocess.call(cmd, shell=True, env=env) 457 if retcode < 0: 458 raise RLException("command [%s] failed with exit code %s"%(cmd, retcode)) 459 except OSError, e: 460 raise RLException("command [%s] failed: %s"%(cmd, e))
461 462 #TODO: _launch_run_executables, _launch_teardown_executables 463 #TODO: define and implement behavior for remote launch
465 """ 466 @raise RLException: if exectuable fails. Failure includes non-zero exit code. 467 """ 468 exes = [e for e in self.config.executables if e.phase == PHASE_SETUP] 469 for e in exes: 470 self._launch_executable(e)
471
472 - def _launch_core_nodes(self):
473 """ 474 launch any core services that are not already running. master must 475 be already running 476 @raise RLException: if core launches fail 477 """ 478 import roslib.names 479 480 config = self.config 481 master = config.master.get() 482 tolaunch = [] 483 for node in config.nodes_core: 484 node_name = roslib.names.ns_join(node.namespace, node.name) 485 code, msg, _ = master.lookupNode(_ID, node_name) 486 if code == -1: 487 tolaunch.append(node) 488 elif code == 1: 489 print "core service [%s] found"%node_name 490 else: 491 print >> sys.stderr, "WARN: master is not behaving well (unexpected return value when looking up node)" 492 self.logger.error("ERROR: master return [%s][%s] on lookupNode call"%(code,msg)) 493 494 for node in tolaunch: 495 node_name = roslib.names.ns_join(node.namespace, node.name) 496 name, success = self.launch_node(node, core=True) 497 if success: 498 print "started core service [%s]"%node_name 499 else: 500 raise RLException("failed to start core service [%s]"%node_name)
501
502 - def launch_node(self, node, core=False):
503 """ 504 Launch a single node locally. Remote launching is handled separately by the remote module. 505 If node name is not assigned, one will be created for it. 506 507 @param node Node: node to launch 508 @param core bool: if True, core node 509 @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name. 510 """ 511 self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type) 512 513 # TODO: should this always override, per spec?. I added this 514 # so that this api can be called w/o having to go through an 515 # extra assign machines step. 516 if node.machine is None: 517 node.machine = self.config.machines[''] 518 if node.name is None: 519 node.name = roslib.names.anonymous_name(node.type) 520 521 master = self.config.master 522 import roslaunch.node_args 523 try: 524 process = create_node_process(self.run_id, node, master.uri) 525 except roslaunch.node_args.NodeParamsException, e: 526 self.logger.error(e) 527 if node.package == 'rosout' and node.type == 'rosout': 528 printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n") 529 else: 530 printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e))) 531 if node.name: 532 return node.name, False 533 else: 534 return "%s/%s"%(node.package,node.type), False 535 536 self.logger.info("... created process [%s]", process.name) 537 if core: 538 self.pm.register_core_proc(process) 539 else: 540 self.pm.register(process) 541 node.process_name = process.name #store this in the node object for easy reference 542 self.logger.info("... registered process [%s]", process.name) 543 544 # note: this may raise FatalProcessLaunch, which aborts the entire launch 545 success = process.start() 546 if not success: 547 if node.machine.name: 548 printerrlog("launch of %s/%s on %s failed"%(node.package, node.type, node.machine.name)) 549 else: 550 printerrlog("local launch of %s/%s failed"%(node.package, node.type)) 551 else: 552 self.logger.info("... successfully launched [%s]", process.name) 553 return process, success
554
555 - def is_node_running(self, node):
556 """ 557 Check for running node process. 558 @param node Node: node object to check 559 @return bool: True if process associated with node is running (launched && !dead) 560 """ 561 #process_name is not set until node is launched. 562 return node.process_name and self.pm.has_process(node.process_name)
563
564 - def spin_once(self):
565 """ 566 Same as spin() but only does one cycle. must be run from the main thread. 567 """ 568 if not self.pm: 569 return False 570 return self.pm.mainthread_spin_once()
571
572 - def spin(self):
573 """ 574 spin() must be run from the main thread. spin() is very 575 important for roslaunch as it picks up jobs that the process 576 monitor need to be run in the main thread. 577 """ 578 self.logger.info("spin") 579 580 # #556: if we're just setting parameters and aren't launching 581 # any processes, exit. 582 if not self.pm or not self.pm.get_active_names(): 583 printlog_bold("No processes to monitor") 584 self.stop() 585 return # no processes 586 self.pm.mainthread_spin() 587 #self.pm.join() 588 self.logger.info("process monitor is done spinning, initiating full shutdown") 589 self.stop() 590 printlog_bold("done")
591
592 - def stop(self):
593 """ 594 Stop the launch and all associated processes. not thread-safe. 595 """ 596 self.logger.info("runner.stop()") 597 if self.pm is not None: 598 printlog("shutting down processing monitor...") 599 self.logger.info("shutting down processing monitor %s"%self.pm) 600 self.pm.shutdown() 601 self.pm.join() 602 self.pm = None 603 printlog("... shutting down processing monitor complete") 604 else: 605 self.logger.info("... roslaunch runner has already been stopped")
606
607 - def _setup(self):
608 """ 609 Setup the state of the ROS network, including the parameter 610 server state and core services 611 """ 612 # this may have already been done, but do just in case 613 self.config.assign_machines() 614 615 if self.remote_runner: 616 # hook in our listener aggregator 617 self.remote_runner.add_process_listener(self.listeners) 618 619 # start up the core: master + core nodes defined in core.xml 620 self._launch_master() 621 self._launch_core_nodes() 622 623 # run exectuables marked as setup period. this will block 624 # until these executables exit. setup executable have to run 625 # *before* parameters are uploaded so that commands like 626 # rosparam delete can execute. 627 self._launch_setup_executables() 628 629 # no parameters for a child process 630 if not self.is_child: 631 self._load_parameters()
632
633 - def launch(self):
634 """ 635 Run the launch. Depending on usage, caller should call 636 spin_once or spin as appropriate after launch(). 637 @return ([str], [str]): tuple containing list of nodes that 638 successfully launches and list of nodes that failed to launch 639 @rtype: ([str], [str]) 640 @raise RLException: if launch fails (e.g. run_id parameter does 641 not match ID on parameter server) 642 """ 643 try: 644 self._setup() 645 succeeded, failed = self._launch_nodes() 646 return succeeded, failed 647 except KeyboardInterrupt: 648 self.stop() 649 raise
650
651 - def run_test(self, test):
652 """ 653 Run the test node. Blocks until completion or timeout. 654 @param test: test node to run 655 @type test: Test 656 @raise RLTestTimeoutException: if test fails to launch or test times out 657 """ 658 self.logger.info("... preparing to run test [%s] of type [%s/%s]", test.test_name, test.package, test.type) 659 proc_h, success = self.launch_node(test) 660 if not success: 661 raise RLException("test [%s] failed to launch"%test.test_name) 662 663 #poll until test terminates or alloted time exceed 664 timeout_t = time.time() + test.time_limit 665 pm = self.pm 666 while pm.mainthread_spin_once() and self.is_node_running(test): 667 #test fails on timeout 668 if time.time() > timeout_t: 669 raise RLTestTimeoutException("test max time allotted") 670 time.sleep(0.1)
671 672 # NOTE: the mainly exists to prevent implicit circular dependency as 673 # the runner needs to invoke methods on the remote API, which depends 674 # on launch. 675
676 -class ROSRemoteRunnerIF(object):
677 """ 678 API for remote running 679 """
680 - def __init__(self):
681 pass
682 - def setup(self):
683 pass
684 - def add_process_listener(self, l):
685 """ 686 Listen to events about remote processes dying. Not 687 threadsafe. Must be called before processes started. 688 @param l: listener 689 @type l: L{ProcessListener} 690 """ 691 pass
692
693 - def launch_remote_nodes(self):
694 """ 695 Contact each child to launch remote nodes 696 @return: succeeded, failed 697 @rtype: [str], [str] 698 """ 699 pass
700