def launch(self, launch_xml): """ Launch the roslaunch XML file. Because this is a child roslaunch, it will not set parameters nor manipulate the master. Call blocks until launch is complete @param xml: roslaunch XML file to launch @type xml: str @return: code, msg, [ [ successful launches], [failed launches] ] @rtype: int, str, [ [str], [str] ] """ if self.pm is None: return 0, "uninitialized", -1 rosconfig = roslaunch.config.ROSLaunchConfig() try: roslaunch.xmlloader.XmlLoader().load_string(launch_xml, rosconfig) except roslaunch.xmlloader.XmlParseException as e: return -1, "ERROR: %s"%e, [[], []] # won't actually do anything other than local, but still required rosconfig.assign_machines() try: # roslaunch clients try to behave like normal roslaunches as much as possible. It's # mainly the responsibility of the roslaunch server to not give us any XML that might # cause conflict (e.g. master tags, param tags, etc...). self._log(Log.INFO, "launching nodes...") runner = ROSLaunchRunner(self.run_id, rosconfig, server_uri=self.server_uri, pmon=self.pm) succeeded, failed = runner.launch() self._log(Log.INFO, "... done launching nodes") # enable the process monitor to exit of all processes die self.pm.registrations_complete() return 1, "launched", [ succeeded, failed ] except Exception as e: return 0, "ERROR: %s"%traceback.format_exc(), [[], []]
def launch(self): config = ROSLaunchConfig() loader = XmlLoader() path = app.getPackagePath(self.app.package) print "pkgpath", path print "launchfile", self.app.launch_file #os.chdir(pkgpath) fn = os.path.join(path, self.app.launch_file) try: loader.load(fn, config) except: self.task.status = "error" #self.manager.app_update.publish(self.task) self.manager._send_status() return self.runner = ROSLaunchRunner(rospy.get_param("/run_id"), config, is_core=False) self.runner.pm.add_process_listener(self) self.runner.launch()
class ROSLaunchChildHandler(ROSLaunchBaseHandler): """ XML-RPC API implementation for child roslaunches NOTE: the client handler runs a process monitor so that it can track processes across requests """ def __init__(self, run_id, name, server_uri, pm): """ @param server_uri: XML-RPC URI of server @type server_uri: str @param pm: process monitor to use @type pm: L{ProcessMonitor} @raise RLException: If parameters are invalid """ super(ROSLaunchChildHandler, self).__init__(pm) if server_uri is None: raise RLException("server_uri is not initialized") self.run_id = run_id # parse the URI to make sure it's valid _, urlport = network.parse_http_host_and_port(server_uri) if urlport <= 0: raise RLException( "ERROR: roslaunch server URI is not a valid XML-RPC URI. Value is [%s]" % m.uri) self.name = name self.pm = pm self.server_uri = server_uri self.server = xmlrpclib.ServerProxy(server_uri) def _shutdown(self, reason): """ xmlrpc.XmlRpcHandler API: inform handler of shutdown @param reason: human-readable shutdown reason @type reason: str """ if self.pm is not None: self.pm.shutdown() self.pm.join() self.pm = None def shutdown(self): """ @return: code, msg, ignore @rtype: int, str, int """ self._shutdown("external call") return 1, "success", 1 def _log(self, level, message): """ log message to log file and roslaunch server @param level: log level @type level: int @param message: message to log @type message: str """ try: if self.logger is not None: self.logger.debug(message) if self.server is not None: self.server.log(str(self.name), level, str(message)) except: self.logger.error(traceback.format_exc()) def launch(self, launch_xml): """ Launch the roslaunch XML file. Because this is a child roslaunch, it will not set parameters nor manipulate the master. Call blocks until launch is complete @param xml: roslaunch XML file to launch @type xml: str @return: code, msg, [ [ successful launches], [failed launches] ] @rtype: int, str, [ [str], [str] ] """ if self.pm is None: return 0, "uninitialized", -1 rosconfig = roslaunch.config.ROSLaunchConfig() try: roslaunch.xmlloader.XmlLoader().load_string(launch_xml, rosconfig) except roslaunch.xmlloader.XmlParseException, e: return -1, "ERROR: %s" % e, [[], []] # check environment settings in config rosconfig.validate() # won't actually do anything other than local, but still required rosconfig.assign_machines() try: # roslaunch clients try to behave like normal roslaunches as much as possible. It's # mainly the responsibility of the roslaunch server to not give us any XML that might # cause conflict (e.g. master tags, param tags, etc...). self._log(Log.INFO, "launching nodes...") runner = ROSLaunchRunner(self.run_id, rosconfig, server_uri=self.server_uri, pmon=self.pm) succeeded, failed = runner.launch() self._log(Log.INFO, "... done launching nodes") # enable the process monitor to exit of all processes die self.pm.registrations_complete() return 1, "launched", [succeeded, failed] except Exception, e: return 0, "ERROR: %s" % traceback.format_exc(), [[], []]
class AppRunner: def __init__(self, taskid, manager): self.taskid = taskid self.task = AppUpdate(None, None, None, None, None) self.app = None self.runner = None self.childGroups = [] self.manager = manager def __del__(self): if self.manager: self.manager = None if self.childGroups: self.childGroups = None def launch(self): config = ROSLaunchConfig() loader = XmlLoader() path = app.getPackagePath(self.app.package) print "pkgpath", path print "launchfile", self.app.launch_file #os.chdir(pkgpath) fn = os.path.join(path, self.app.launch_file) try: loader.load(fn, config) except: self.task.status = "error" #self.manager.app_update.publish(self.task) self.manager._send_status() return self.runner = ROSLaunchRunner(rospy.get_param("/run_id"), config, is_core=False) self.runner.pm.add_process_listener(self) self.runner.launch() def stop(self): if not self.runner: print "no runner", self return self.runner.stop() self.runner = None def process_died(self, process_name, exit_code): #print "process_died", process_name, exit_code #print self.runner.pm.procs if not self.runner: return if len(self.runner.pm.procs) == 1: self.runner = None print "ALL DONE!" self.manager._stopTask(self) else: if self.runner.pm.procs: self.task.status = "error" self.manager._send_status() print "too many processes left:", len(self.runner.pm.procs) for proc in self.runner.pm.procs: proc.stop() self.runner = None self.manager._stopTask(self) def __repr__(self): return "<AppRunner %s: %s %s %s>" % (self.taskid, self.app.provides, self.app.taskid, len(self.childGroups))