roslaunch: #1876 protect against multiple shutdown attempts, and epydoc conversion
This commit is contained in:
parent
183be99b89
commit
d44adbb3ae
|
@ -32,6 +32,14 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""
|
||||
roslaunch.parent providees the L{ROSLaunchParent} implementation,
|
||||
which represents the main 'parent' roslaunch process. In the roslaunch
|
||||
architecture, the parent is responsible for bringing up child
|
||||
roslaunches on other machines and coordinating the process launch. It
|
||||
will also bring up any local processes.
|
||||
"""
|
||||
|
||||
import logging
|
||||
import sys
|
||||
|
||||
|
@ -48,22 +56,31 @@ import roslaunch.xmlloader
|
|||
# qualification accesses this API, which has been relocated
|
||||
load_config_default = roslaunch.config.load_config_default
|
||||
|
||||
## ROSLaunchParent represents the main 'parent' roslaunch process. It
|
||||
## is responsible for loading the launch files, assigning machines,
|
||||
## and then starting up any remote processes. The __main__ method
|
||||
## delegates most of runtime to ROSLaunchParent.
|
||||
class ROSLaunchParent(object):
|
||||
"""
|
||||
ROSLaunchParent represents the main 'parent' roslaunch process. It
|
||||
is responsible for loading the launch files, assigning machines,
|
||||
and then starting up any remote processes. The __main__ method
|
||||
delegates most of runtime to ROSLaunchParent.
|
||||
"""
|
||||
|
||||
## @param run_id str: UUID of roslaunch session
|
||||
## @param roslaunch_files [str]: list of launch configuration
|
||||
## files to load
|
||||
## @param is_core bool: if True, this launch is a roscore
|
||||
## instance. This affects the error behavior if a master is
|
||||
## already running (i.e. it fails).
|
||||
## @param process_listeners: (optional) list of process listeners
|
||||
## to register with process monitor once launch is running
|
||||
## @throws RLException
|
||||
def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only=False, process_listeners=None):
|
||||
"""
|
||||
@param run_id: UUID of roslaunch session
|
||||
@type run_id: str
|
||||
@param roslaunch_files: list of launch configuration
|
||||
files to load
|
||||
@type roslaunch_files: [str]
|
||||
@param is_core bool: if True, this launch is a roscore
|
||||
instance. This affects the error behavior if a master is
|
||||
already running (i.e. it fails).
|
||||
@type is_core: bool
|
||||
@param process_listeners: (optional) list of process listeners
|
||||
to register with process monitor once launch is running
|
||||
@type process_listeners: [L{roslaunch.pmon.ProcessListener}]
|
||||
@throws RLException
|
||||
"""
|
||||
|
||||
self.logger = logging.getLogger('roslaunch.parent')
|
||||
self.run_id = run_id
|
||||
self.process_listeners = process_listeners
|
||||
|
@ -73,19 +90,24 @@ class ROSLaunchParent(object):
|
|||
self.port = port
|
||||
self.local_only = local_only
|
||||
|
||||
# flag to prevent multiple shutdown attempts
|
||||
self._shutting_down = False
|
||||
|
||||
self.config = self.runner = self.server = self.pm = self.remote_runner = None
|
||||
|
||||
def _load_config(self):
|
||||
self.config = roslaunch.config.load_config_default(self.roslaunch_files, self.port)
|
||||
|
||||
## Start the process monitor
|
||||
## @param self
|
||||
def _start_pm(self):
|
||||
"""
|
||||
Start the process monitor
|
||||
"""
|
||||
self.pm = roslaunch.pmon.start_process_monitor()
|
||||
|
||||
## Initialize the roslaunch runner
|
||||
## @param self
|
||||
def _init_runner(self):
|
||||
"""
|
||||
Initialize the roslaunch runner
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
|
@ -100,9 +122,10 @@ class ROSLaunchParent(object):
|
|||
for err in self.config.config_errors:
|
||||
printerrlog("WARNING: %s"%err)
|
||||
|
||||
## Initialize the roslaunch parent XML-RPC server
|
||||
## @param self
|
||||
def _start_server(self):
|
||||
"""
|
||||
Initialize the roslaunch parent XML-RPC server
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
|
@ -115,10 +138,11 @@ class ROSLaunchParent(object):
|
|||
raise RLException("server URI did not initialize")
|
||||
self.logger.info("... parent XML-RPC server started")
|
||||
|
||||
## Initialize the remote process runner, if required. Subroutine
|
||||
## of _start_remote, separated out for easier testing
|
||||
## @param self
|
||||
def _init_remote(self):
|
||||
"""
|
||||
Initialize the remote process runner, if required. Subroutine
|
||||
of _start_remote, separated out for easier testing
|
||||
"""
|
||||
if self.config is None:
|
||||
raise RLException("config is not initialized")
|
||||
if self.pm is None:
|
||||
|
@ -127,22 +151,25 @@ class ROSLaunchParent(object):
|
|||
raise RLException("server is not initialized")
|
||||
|
||||
if not self.local_only and self.config.has_remote_nodes():
|
||||
## keep the remote package lazy-imported
|
||||
# keep the remote package lazy-imported
|
||||
import roslaunch.remote
|
||||
self.remote_runner = roslaunch.remote.ROSRemoteRunner(self.run_id, self.config, self.pm, self.server)
|
||||
elif self.local_only:
|
||||
printlog_bold("LOCAL\nlocal only launch specified, will not launch remote nodes\nLOCAL\n")
|
||||
|
||||
## Initializes and runs the remote process runner, if required
|
||||
def _start_remote(self):
|
||||
"""
|
||||
Initializes and runs the remote process runner, if required
|
||||
"""
|
||||
self._init_remote()
|
||||
if self.remote_runner is not None:
|
||||
# start_servers() runs the roslaunch children
|
||||
self.remote_runner.start_children()
|
||||
|
||||
## load config, start XMLRPC servers and process monitor
|
||||
## @param self
|
||||
def _start_infrastructure(self):
|
||||
"""
|
||||
load config, start XMLRPC servers and process monitor
|
||||
"""
|
||||
self._load_config()
|
||||
|
||||
# Start the process monitor
|
||||
|
@ -156,17 +183,27 @@ class ROSLaunchParent(object):
|
|||
# Requires config, pm, and server
|
||||
self._start_remote()
|
||||
|
||||
## tear down server and process monitor
|
||||
def _stop_infrastructure(self):
|
||||
"""
|
||||
Tear down server and process monitor. Not multithread safe.
|
||||
"""
|
||||
#TODO more explicit teardown of remote infrastructure
|
||||
|
||||
# test and set flag so we don't shutdown multiple times
|
||||
if self._shutting_down:
|
||||
return
|
||||
self._shutting_down = True
|
||||
|
||||
if self.server:
|
||||
self.server.shutdown("roslaunch parent complete")
|
||||
if self.pm:
|
||||
self.pm.shutdown()
|
||||
self.pm.join()
|
||||
|
||||
## Run the parent roslaunch
|
||||
def start(self):
|
||||
"""
|
||||
Run the parent roslaunch
|
||||
"""
|
||||
self.logger.info("starting roslaunch parent run")
|
||||
|
||||
# load config, start XMLRPC servers and process monitor
|
||||
|
@ -184,11 +221,16 @@ class ROSLaunchParent(object):
|
|||
self.runner.pm.add_process_listener(l)
|
||||
|
||||
def spin_once(self):
|
||||
"""
|
||||
Run the parent roslaunch event loop once
|
||||
"""
|
||||
if self.runner:
|
||||
self.runner.spin_once()
|
||||
|
||||
## Run the parent roslaunch
|
||||
def spin(self):
|
||||
"""
|
||||
Run the parent roslaunch until exit
|
||||
"""
|
||||
if not self.runner:
|
||||
raise RLException("parent not started yet")
|
||||
try:
|
||||
|
@ -198,4 +240,7 @@ class ROSLaunchParent(object):
|
|||
self._stop_infrastructure()
|
||||
|
||||
def shutdown(self):
|
||||
"""
|
||||
Stop the parent roslaunch.
|
||||
"""
|
||||
self._stop_infrastructure()
|
||||
|
|
Loading…
Reference in New Issue