Пример #1
0
    def __init__(self, run_id, name, server_uri, pm, sigint_timeout=DEFAULT_TIMEOUT_SIGINT, sigterm_timeout=DEFAULT_TIMEOUT_SIGTERM):
        """
        @param server_uri: XML-RPC URI of server
        @type  server_uri: str
        @param pm: process monitor to use
        @type  pm: L{ProcessMonitor}
        @param sigint_timeout: The SIGINT timeout used when killing nodes (in seconds).
        @type  sigint_timeout: float
        @param sigterm_timeout: The SIGTERM timeout used when killing nodes if SIGINT does not stop the node (
                                in seconds).
        @type  sigterm_timeout: float
        @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.sigint_timeout = sigint_timeout
        self.sigterm_timeout = sigterm_timeout
        self.server = ServerProxy(server_uri)
Пример #2
0
    def _init_runner(self):
        """
        Initialize the roslaunch runner
        """
        if self.config is None:
            raise RLException("config is not initialized")
        if self.pm is None:
            raise RLException("pm is not initialized")
        if self.server is None:
            raise RLException("server is not initialized")
        self.runner = roslaunch.launch.ROSLaunchRunner(
            self.run_id,
            self.config,
            server_uri=self.server.uri,
            pmon=self.pm,
            is_core=self.is_core,
            remote_runner=self.remote_runner,
            is_rostest=self.is_rostest)

        # print runner info to user, put errors last to make the more visible
        if self.is_core:
            print("ros_comm version %s" %
                  (self.config.params['/rosversion'].value))

        print(self.config.summary(local=self.remote_runner is None))
        if self.config:
            for err in self.config.config_errors:
                printerrlog("WARNING: %s" % err)
    def _create_launchconfig(self,
                             launchfile_name,
                             port_roscore=11311,
                             folder_name_launchfile='launch'):
        '''
        @rtype: ROSLaunchConfig
        @raises RLException: raised by roslaunch.config.load_config_default.
        '''

        pkg_name = self._combobox_pkg.currentText()

        try:
            launchfile = os.path.join(self._rospack.get_path(pkg_name),
                                      folder_name_launchfile, launchfile_name)
        except IndexError as e:
            raise RLException('IndexError: {}'.format(e.message))

        try:
            launch_config = roslaunch.config.load_config_default([launchfile],
                                                                 port_roscore)
        except rospkg.common.ResourceNotFound as e:
            raise RLException('ResourceNotFound: {}'.format(e.message))
        except RLException as e:
            raise e

        return launch_config
Пример #4
0
    def _register_with_server(self):
        """
        Register child node with server
        """        
        name = self.name
        self.logger.info("attempting to register with roslaunch parent [%s]"%self.server_uri)
        try:
            server = ServerProxy(self.server_uri)
            code, msg, _ = server.register(name, self.uri)
            if code != 1:
                raise RLException("unable to register with roslaunch server: %s"%msg)
        except Exception as e:
            self.logger.error("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc()))
            # fail
            raise RLException("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc()))
        
        self.logger.debug("child registered with server")
        
        # register printlog handler so messages are funneled to remote
        def serverlog(msg):
            server.log(name, Log.INFO, msg)
        def servererrlog(msg):
            server.log(name, Log.ERROR, msg)
        add_printlog_handler(serverlog)
        add_printerrlog_handler(servererrlog)            

        # register process listener to forward process death events to main server
        self.pm.add_process_listener(_ProcessListenerForwarder(server))
Пример #5
0
    def start_children(self):
        """
        Start the child roslaunch processes
        """
        server_node_uri = self.server.uri
        if not server_node_uri:
            raise RLException("server URI is not initialized")
        
        # TODOXXX: break out table building code into a separate
        # routine so we can unit test it _start_child() should not be
        # determining the process name

        # Build table of unique machines that we are going to launch on
        machines = {}
        for n in self.rosconfig.nodes:
            if not is_machine_local(n.machine):
                machines[n.machine.config_key()] = n.machine

        # Launch child roslaunch processes on remote machines
        counter = 0
        #  - keep a list of procs so we can check for those that failed to launch
        procs = []
        for m in machines:
            p = self._start_child(server_node_uri, machines[m], counter)
            procs.append(p)
            counter += 1
        
        # Wait for all children to call register() callback. The machines can have
        # non-uniform registration timeouts. We consider the failure to occur once
        # one of the machines has failed to meet it's timeout.
        start_t = time.time() 
        while True:
            pending = []
            for p in procs:
                if not p.is_alive():
                    raise RLException("remote roslaunch failed to launch: %s"%p.machine.name)
                elif not p.uri:
                    pending.append(p.machine)
            if not pending:
                break
            # timeout is the minimum of the remaining timeouts of the machines
            timeout_t = start_t + min([m.timeout for m in pending])
            if time.time() > timeout_t:
                break
            time.sleep(0.1)
        if pending:
            raise RLException(
                """The following roslaunch remote processes failed to register: 
%s

If this is a network latency issue, you may wish to consider setting 
  <machine timeout="NUMBER OF SECONDS" ... />
in your launch"""%'\n'.join([" * %s (timeout %ss)"%(m.name, m.timeout) for m in pending]))

        # convert machine dictionary to a list
        self.machine_list = machines.values()
        # save a list of the remote processes
        self.remote_processes = procs
Пример #6
0
    def start(self):
        """
        Startup roslaunch server XML-RPC services
        @raise RLException: if server fails to start
        """
        logger = logging.getLogger('roslaunch.server')
        logger.info("starting roslaunch XML-RPC server")
        super(ROSLaunchNode, self).start()

        # wait for node thread to initialize
        timeout_t = time.time() + _STARTUP_TIMEOUT
        logger.info("waiting for roslaunch XML-RPC server to initialize")
        while not self.uri and time.time() < timeout_t:
            time.sleep(0.01)
        if not self.uri:
            raise RLException("XML-RPC initialization failed")

        # Make sure our xmlrpc server is actually up. We've seen very
        # odd cases where remote nodes are unable to contact the
        # server but have been unable to prove this is the cause.
        server_up = False
        while not server_up and time.time() < timeout_t:
            try:
                code, msg, val = ServerProxy(self.uri).get_pid()
                if val != os.getpid():
                    raise RLException(
                        "Server at [%s] did not respond with correct PID. There appears to be something wrong with the networking configuration"
                        % self.uri)
                server_up = True
            except IOError:
                # presumably this can occur if we call in a small time
                # interval between the server socket port being
                # assigned and the XMLRPC server initializing, but it
                # is highly unlikely and unconfirmed
                time.sleep(0.1)
            except socket.error as e:
                if e.errno == 113:
                    p = urlparse(self.uri)
                    raise RLException(
                        "Unable to contact the address [%s], which should be local.\nThis is generally caused by:\n * bad local network configuration\n * bad ROS_IP environment variable\n * bad ROS_HOSTNAME environment variable\nCan you ping %s?"
                        % (self.uri, p.hostname))
                else:
                    time.sleep(0.1)
        if not server_up:
            p = urlparse(self.uri)
            raise RLException("""Unable to contact my own server at [%s].
This usually means that the network is not configured properly.

A common cause is that the machine cannot connect to itself.  Please check
for errors by running:

\tping %s

For more tips, please see

\thttp://www.ros.org/wiki/ROS/NetworkSetup
""" % (self.uri, p.hostname))
        printlog_bold("started roslaunch server %s" % (self.uri))
Пример #7
0
def get_node_args(node_name, roslaunch_files):
    """
    Get the node arguments for a node in roslaunch_files. 

    @param node_name: name of node in roslaunch_files.
    @type  node_name: str
    @param roslaunch_files: roslaunch file names
    @type  roslaunch_files: [str]
    @return: list of command-line arguments used to launch node_name
    @rtype: [str]
    @raise RLException: if node args cannot be retrieved
    """

    # we have to create our own XmlLoader so that we can use the same
    # resolution context for substitution args

    loader = roslaunch.xmlloader.XmlLoader(resolve_anon=False)
    config = load_config_default(roslaunch_files,
                                 None,
                                 loader=loader,
                                 verbose=False,
                                 assign_machines=False)
    (node_name) = substitution_args.resolve_args((node_name),
                                                 resolve_anon=False)
    node_name = script_resolve_name(
        'roslaunch', node_name) if not node_name.startswith('$') else node_name

    node = [n for n in config.nodes if _resolved_name(n) == node_name] + \
        [n for n in config.tests if _resolved_name(n) == node_name]
    if not node:
        node_list = get_node_list(config)
        node_list_str = '\n'.join([" * %s" % x for x in node_list])
        raise RLException(
            "ERROR: Cannot find node named [%s] in [%s].\nNode names are:\n%s"
            % (node_name, ', '.join(roslaunch_files), node_list_str))
    elif len(node) > 1:
        raise RLException(
            "ERROR: multiple nodes named [%s] in [%s].\nPlease fix the launch files as duplicate names are not allowed."
            % (node_name, ', '.join(roslaunch_files)))
    node = node[0]

    master_uri = rosgraph.get_master_uri()
    machine = local_machine()
    env = setup_env(node, machine, master_uri)

    # remove setting identical to current environment for easier debugging
    to_remove = []
    for k in env.keys():
        if env[k] == os.environ.get(k, None):
            to_remove.append(k)
    for k in to_remove:
        del env[k]

    # resolve node name for generating args
    args = create_local_process_args(node, machine)
    # join environment vars are bash prefix args
    return ["%s=%s" % (k, v) for k, v in env.items()] + args
Пример #8
0
def load_config_default(roslaunch_files,
                        port,
                        roslaunch_strs=None,
                        loader=None,
                        verbose=False,
                        assign_machines=True):
    """
    Base routine for creating a ROSLaunchConfig from a set of 
    roslaunch_files and or launch XML strings and initializing it. This
    config will have a core definition and also set the master to run
    on port.
    @param roslaunch_files: list of launch files to load
    @type  roslaunch_files: [str]
    @param port: roscore/master port override. Set to 0 or None to use default.
    @type  port: int
    @param roslaunch_strs: (optional) roslaunch XML strings to load
    @type  roslaunch_strs: [str]
    @param verbose: (optional) print info to screen about model as it is loaded. 
    @type  verbose: bool
    @param assign_machines: (optional) assign nodes to machines (default: True)
    @type  assign_machines: bool
    @return: initialized rosconfig instance
    @rytpe: L{ROSLaunchConfig} initialized rosconfig instance
    """
    logger = logging.getLogger('roslaunch.config')

    # This is the main roslaunch server process. Load up the
    # files specified on the command line and launch the
    # requested resourcs.

    config = ROSLaunchConfig()
    if port:
        config.master.uri = roslib.network.create_local_xmlrpc_uri(port)

    loader = loader or roslaunch.xmlloader.XmlLoader()

    # load the roscore file first. we currently have
    # last-declaration wins rules.  roscore is just a
    # roslaunch file with special load semantics
    load_roscore(loader, config, verbose=verbose)

    # load the roslaunch_files into the config
    for f in roslaunch_files:
        try:
            logger.info('loading config file %s' % f)
            loader.load(f, config, verbose=verbose)
        except roslaunch.xmlloader.XmlParseException, e:
            raise RLException(e)
        except roslaunch.loader.LoadException, e:
            raise RLException(e)
Пример #9
0
    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:
            raise RLException("pm is not initialized")

        self.logger.info("starting parent XML-RPC server")
        self.server = roslaunch.server.ROSLaunchParentNode(self.config, self.pm)
        self.server.start()
        if not self.server.uri:
            raise RLException("server URI did not initialize")
        self.logger.info("... parent XML-RPC server started")        
Пример #10
0
 def add_machine(self, m, verbose=True):
     """
     Declare a machine and associated parameters so that it can be used for
     running nodes.
     @param m: machine instance
     @type  m: L{Machine}
     @return: True if new machine added, False if machine already specified.
     @rtype: bool
     @raise RLException: if cannot add machine as specified
     """
     name = m.name
     if m.address == 'localhost':  #simplify address comparison
         import roslib.network
         address = roslib.network.get_local_address()
         self.logger.info(
             "addMachine[%s]: remapping localhost address to %s" %
             (name, address))
     if name in self.machines:
         if m != self.machines[name]:
             raise RLException(
                 "Machine [%s] already added and does not match duplicate entry"
                 % name)
         return False
     else:
         self.machines[name] = m
         if verbose:
             print "Added machine [%s]" % name
         return True
Пример #11
0
def print_node_filename(node_name, roslaunch_files):
    try:
        # #2309
        node_name = script_resolve_name('roslaunch', node_name)

        loader = roslaunch.xmlloader.XmlLoader(resolve_anon=False)
        config = load_config_default(roslaunch_files,
                                     None,
                                     loader=loader,
                                     verbose=False,
                                     assign_machines=False)
        nodes = [n for n in config.nodes if _resolved_name(n) == node_name] + \
            [t for t in config.tests if _resolved_name(t) == node_name]

        if len(nodes) > 1:
            raise RLException(
                "ERROR: multiple nodes named [%s] in [%s].\nPlease fix the launch files as duplicate names are not allowed."
                % (node_name, ', '.join(roslaunch_files)))
        if not nodes:
            print(
                'ERROR: cannot find node named [%s]. Run \n\troslaunch --nodes <files>\nto see list of node names.'
                % (node_name),
                file=sys.stderr)
        else:
            print(nodes[0].filename)

    except RLException as e:
        print(str(e), file=sys.stderr)
        sys.exit(1)
Пример #12
0
 def __init__(self, run_id, name, server_uri, pm, sigint_timeout=DEFAULT_TIMEOUT_SIGINT, sigterm_timeout=DEFAULT_TIMEOUT_SIGTERM):
     """
 ## Startup roslaunch remote client XML-RPC services. Blocks until shutdown
 ## @param name: name of remote client
 ## @type  name: str
 ## @param server_uri: XML-RPC URI of roslaunch server
 ## @type  server_uri: str
 ## @param sigint_timeout: The SIGINT timeout used when killing nodes (in seconds).
 ## @type  sigint_timeout: float
 ## @param sigterm_timeout: The SIGTERM timeout used when killing nodes if SIGINT does not stop the node (
 ##                         in seconds).
 ## @type  sigterm_timeout: float
 ## @return: XML-RPC URI
 ## @rtype: str
     """        
     self.logger = logging.getLogger("roslaunch.server")
     self.run_id = run_id
     self.name = name
     self.server_uri = server_uri
     self.pm = pm
     
     if self.pm is None:
         raise RLException("cannot create child node: pm is not initialized")
     handler = ROSLaunchChildHandler(self.run_id, self.name, self.server_uri, self.pm,
                                     sigint_timeout=sigint_timeout, sigterm_timeout=sigterm_timeout)
     super(ROSLaunchChildNode, self).__init__(handler)
Пример #13
0
 def kill_process(self, name):
     """
     Kill process that matches name. NOTE: a killed process will
     continue to show up as active until the process monitor thread
     has caught that it has died.
     @param name: Process name
     @type  name: str
     @return: True if a process named name was removed from
     process monitor. A process is considered killed if its stop()
     method was called.
     @rtype: bool
     """
     if not isinstance(name, basestring):
         raise RLException(
             "kill_process takes in a process name but was given: %s" %
             name)
     logger.debug("ProcessMonitor.kill_process[%s]" % name)
     printlog("[%s] kill requested" % name)
     with self.plock:
         p = self.get_process(name)
         if p:
             try:
                 # no need to accumulate errors, so pass in []
                 p.stop([])
             except:
                 logger.error(traceback.format_exc())
             return True
         else:
             return False
Пример #14
0
class ROSLaunchNode(xmlrpc.XmlRpcNode):
    """
    Base XML-RPC server for roslaunch parent/child processes
    """
    def __init__(self, handler):
        """
        @param handler: xmlrpc api handler
        @type  handler: L{ROSLaunchBaseHandler}
        """
        super(ROSLaunchNode, self).__init__(0, handler)

    def start(self):
        """
        Startup roslaunch server XML-RPC services
        @raise RLException: if server fails to start
        """
        logger = logging.getLogger('roslaunch.server')
        logger.info("starting roslaunch XML-RPC server")
        super(ROSLaunchNode, self).start()

        # wait for node thread to initialize
        timeout_t = time.time() + _STARTUP_TIMEOUT
        logger.info("waiting for roslaunch XML-RPC server to initialize")
        while not self.uri and time.time() < timeout_t:
            time.sleep(0.01)
        if not self.uri:
            raise RLException("XML-RPC initialization failed")

        # Make sure our xmlrpc server is actually up. We've seen very
        # odd cases where remote nodes are unable to contact the
        # server but have been unable to prove this is the cause.
        server_up = False
        while not server_up and time.time() < timeout_t:
            try:
                code, msg, val = xmlrpclib.ServerProxy(self.uri).get_pid()
                if val != os.getpid():
                    raise RLException(
                        "Server at [%s] did not respond with correct PID. There appears to be something wrong with the networking configuration"
                        % self.uri)
                server_up = True
            except IOError:
                # presumably this can occur if we call in a small time
                # interval between the server socket port being
                # assigned and the XMLRPC server initializing, but it
                # is highly unlikely and unconfirmed
                time.sleep(0.1)
            except socket.error, (errno, msg):
                if errno == 113:
                    p = urlparse.urlparse(self.uri)
                    raise RLException(
                        "Unable to contact the address [%s], which should be local.\nThis is generally caused by:\n * bad local network configuration\n * bad ROS_IP environment variable\n * bad ROS_HOSTNAME environment variable\nCan you ping %s?"
                        % (self.uri, p.hostname))
                else:
                    time.sleep(0.1)
        if not server_up:
            raise RLException(
                "Unable to contact my own XML-RPC server, this is a highly unusual error and should be reported immediately.\nMy URI is [%s]"
                % self.uri)
        printlog_bold("started roslaunch server %s" % self.uri)
Пример #15
0
    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:
            raise RLException("pm is not initialized")
        if self.server is None:
            raise RLException("server is not initialized")

        if not self.local_only and self.config.has_remote_nodes():
            # 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")
Пример #16
0
    def launch(self, node):
        """
        Launch a roslaunch node instance
        
        @param node: roslaunch Node instance
        @type  node: roslaunch.Node
        @return: node process
        @rtype: roslaunch.Process
        @raise RLException: if launch fails
        """
        if not self.started:
            raise RLException("please start ROSLaunch first")
        elif not isinstance(node, Node):
            raise ValueError("arg must be of type Node")

        proc, success = self.parent.runner.launch_node(node)
        if not success:
            raise RLException("failed to launch")
        return proc
Пример #17
0
 def add_remap(self, remap):
     """
     Add a new remap setting to the context. if a remap already
     exists with the same from key, it will be removed
     
     @param remap: remap setting
     @type  remap: (str, str)
     """
     remap = [canonicalize_name(x) for x in remap]
     if not remap[0] or not remap[1]:
         raise RLException("remap from/to attributes cannot be empty")
     if not is_legal_name(remap[0]):
         raise RLException("remap from [%s] is not a valid ROS name"%remap[0])
     if not is_legal_name(remap[1]):
         raise RLException("remap to [%s] is not a valid ROS name"%remap[1])
     
     matches = [r for r in self._remap_args if r[0] == remap[0]]
     for m in matches:
         self._remap_args.remove(m)
     self._remap_args.append(remap)
Пример #18
0
 def spin(self):
     """
     Run the parent roslaunch until exit
     """
     if not self.runner:
         raise RLException("parent not started yet")
     try:
         # Blocks until all processes dead/shutdown
         self.runner.spin()
     finally:
         self._stop_infrastructure()
Пример #19
0
 def _register_with_server(self):
     """
     Register child node with server
     """
     name = self.name
     self.logger.info("attempting to register with roslaunch parent [%s]" %
                      self.server_uri)
     try:
         server = xmlrpclib.ServerProxy(self.server_uri)
         code, msg, _ = server.register(name, self.uri)
         if code != 1:
             raise RLException(
                 "unable to register with roslaunch server: %s" % msg)
     except Exception, e:
         self.logger.error(
             "Exception while registering with roslaunch parent [%s]: %s" %
             (self.server_uri, traceback.format_exc(e)))
         # fail
         raise RLException(
             "Exception while registering with roslaunch parent [%s]: %s" %
             (self.server_uri, traceback.format_exc(e)))
Пример #20
0
 def register(self, p):
     """
     Register process with L{ProcessMonitor}
     @param p: Process
     @type  p: L{Process}
     @raise RLException: if process with same name is already registered
     """
     logger.info("ProcessMonitor.register[%s]"%p.name)
     e = None
     with self.plock:
         if self.has_process(p.name):
             e = RLException("cannot add process with duplicate name '%s'"%p.name)
         elif self.is_shutdown:
             e = RLException("cannot add process [%s] after process monitor has been shut down"%p.name)
         else:
             self.procs.append(p)
     if e:
         logger.error("ProcessMonitor.register[%s] failed %s"%(p.name, e))
         raise e
     else:
         logger.info("ProcessMonitor.register[%s] complete"%p.name)
Пример #21
0
    def add_node(self, node, core=False, verbose=True):
        """
        Add node declaration
        @param node: node instance to add to launch
        @type  node: L{Node}
        @param core: if True, node is a ROS core node
        @type  core: bool
        @raise RLException: if ROS core node is missing required name
        """
        if node.name:
            # check for duplicates
            resolved_name = roslib.names.ns_join(node.namespace, node.name)
            matches = [
                n for n in self.resolved_node_names if n == resolved_name
            ]
            if matches:
                raise RLException(
                    "roslaunch file contains multiple nodes named [%s].\nPlease check all <node> 'name' attributes to make sure they are unique.\nAlso check that $(anon id) use different ids."
                    % resolved_name)
            else:
                self.resolved_node_names.append(resolved_name)

        if not core:
            self.nodes.append(node)
            if verbose:
                print "Added node of type [%s/%s] in namespace [%s]" % (
                    node.package, node.type, node.namespace)
            self.logger.info("Added node of type [%s/%s] in namespace [%s]",
                             node.package, node.type, node.namespace)
        else:
            if not node.name:
                raise RLException("ROS core nodes must have a name. [%s/%s]" %
                                  (node.package, node.type))
            self.nodes_core.append(node)
            if verbose:
                print "Added core node of type [%s/%s] in namespace [%s]" % (
                    node.package, node.type, node.namespace)
            self.logger.info(
                "Added core node of type [%s/%s] in namespace [%s]",
                node.package, node.type, node.namespace)
Пример #22
0
 def validate(self):
     """
     Perform basic checks on the local ROS environment, master, and core services.
     master will be launched if configured to do so. Core services will be launched regardless.
     if they are not already running.
 
     @raise RLException: if validation fails
     """
     ros_root = get_ros_root()
     if not os.path.isdir(ros_root):
         raise RLException(
             "ERROR: ROS_ROOT is not configured properly. Value is [%s]" %
             ros_root)
Пример #23
0
    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 = ServerProxy(server_uri)
Пример #24
0
    def __init__(self, rosconfig, pm):
        """
        @param config: ROSConfig launch configuration
        @type  config: L{ROSConfig}
        @param pm: process monitor
        @type  pm: L{ProcessMonitor}
        """
        self.rosconfig = rosconfig
        self.listeners = []
        self.child_processes = {} #{ child-name : ChildROSLaunchProcess}.

        if pm is None:
            raise RLException("cannot create parent node: pm is not initialized")
        handler = ROSLaunchParentHandler(pm, self.child_processes, self.listeners)
        super(ROSLaunchParentNode, self).__init__(handler)
Пример #25
0
    def _start_child(self, server_node_uri, machine, counter):
        # generate a name for the machine. don't use config key as
        # it's too long to easily display
        name = "%s-%s"%(machine.address, counter)

        self.logger.info("remote[%s] starting roslaunch", name)
        print "remote[%s] starting roslaunch"%name
            
        env_dict = setup_env(None, machine, self.rosconfig.master.uri)
        p = SSHChildROSLaunchProcess(self.run_id, name, server_node_uri, env_dict, machine)
        success = p.start()
        self.pm.register(p)
        if not success: #treat as fatal
            raise RLException("unable to start remote roslaunch child: %s"%name)
        self.server.add_child(name, p)
        return p
Пример #26
0
 def __init__(self, run_id, name, server_uri, pm):
     """
 ## Startup roslaunch remote client XML-RPC services. Blocks until shutdown
 ## @param name: name of remote client
 ## @type  name: str
 ## @param server_uri: XML-RPC URI of roslaunch server
 ## @type  server_uri: str
 ## @return: XML-RPC URI
 ## @rtype: str
     """        
     self.logger = logging.getLogger("roslaunch.server")
     self.run_id = run_id
     self.name = name
     self.server_uri = server_uri
     self.pm = pm
     
     if self.pm is None:
         raise RLException("cannot create child node: pm is not initialized")
     handler = ROSLaunchChildHandler(self.run_id, self.name, self.server_uri, self.pm)
     super(ROSLaunchChildNode, self).__init__(handler)
Пример #27
0
 def _select_machine(self, node):
     """
     Select a machine for a node to run on. For nodes that are
     already assigned to a machine, this will map the string name to
     a L{Machine} instance. If the node isn't already tagged with a
     particular machine, one will be selected for it.
     @param node: node to assign machine for
     @type  node: L{Node}
     @return: machine to run on
     @rtype: L{Machine}
     @raise RLException: If machine state is improperly configured
     """
     machine = node.machine_name
     #Lookup machine
     if machine:
         if not machine in self.machines:
             raise RLException("ERROR: unknown machine [%s]" % machine)
         return self.machines[machine]
     else:
         # assign to local machine
         return self.machines['']
Пример #28
0
 def __init__(self, pm):
     self.pm = pm
     self.logger = logging.getLogger('roslaunch.server')
     if self.pm is None:
         raise RLException(
             "cannot create xmlrpc handler: pm is not initialized")
Пример #29
0
    def __init__(self, run_id, roslaunch_files, is_core=False, port=None, local_only=False, process_listeners=None,
            verbose=False, force_screen=False, force_log=False, is_rostest=False, roslaunch_strs=None, num_workers=NUM_WORKERS, timeout=None, master_logger_level=False, show_summary=True, force_required=False,
            sigint_timeout=DEFAULT_TIMEOUT_SIGINT, sigterm_timeout=DEFAULT_TIMEOUT_SIGTERM):
        """
        @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}]
        @param port: (optional) override master port number from what is specified in the master URI.
        @type  port: int
        @param verbose: (optional) print verbose output
        @type  verbose: boolean
        @param show_summary: (optional) whether to show a summary or not
        @type  show_summary: boolean
        @param force_screen: (optional) force output of all nodes to screen
        @type  force_screen: boolean
        @param force_log: (optional) force output of all nodes to log
        @type  force_log: boolean
        @param is_rostest bool: if True, this launch is a rostest
            instance. This affects validation checks.
        @type  is_rostest: bool
        @param num_workers: If this is the core, the number of worker-threads to use.
        @type num_workers: int
        @param timeout: If this is the core, the socket-timeout to use.
        @type timeout: Float or None
        @throws RLException
        @param master_logger_level: Specify roscore's rosmaster.master logger level, use default if it is False.
        @type master_logger_level: str or False
        @param force_required: (optional) whether to make all nodes required
        @type force_required: boolean
        @param sigint_timeout: The SIGINT timeout used when killing nodes (in seconds).
        @type sigint_timeout: float
        @param sigterm_timeout: The SIGTERM timeout used when killing nodes if SIGINT does not stop the node (in seconds).
        @type sigterm_timeout: float
        @raise RLException: If sigint_timeout or sigterm_timeout are nonpositive.
        """
        if sigint_timeout <= 0:
            raise RLException("sigint_timeout must be a positive number, received %f" % sigint_timeout)
        if sigterm_timeout <= 0:
            raise RLException("sigterm_timeout must be a positive number, received %f" % sigterm_timeout)
        
        self.logger = logging.getLogger('roslaunch.parent')
        self.run_id = run_id
        self.process_listeners = process_listeners
        
        self.roslaunch_files = roslaunch_files
        self.roslaunch_strs = roslaunch_strs
        self.is_core = is_core
        self.is_rostest = is_rostest
        self.port = port
        self.local_only = local_only
        self.verbose = verbose
        self.show_summary = show_summary
        self.num_workers = num_workers
        self.timeout = timeout
        self.master_logger_level = master_logger_level
        self.sigint_timeout = sigint_timeout
        self.sigterm_timeout = sigterm_timeout

        # I don't think we should have to pass in so many options from
        # the outside into the roslaunch parent. One possibility is to
        # allow alternate config loaders to be passed in.
        self.force_screen = force_screen
        self.force_log = force_log
        self.force_required = force_required
        
        # flag to prevent multiple shutdown attempts
        self._shutting_down = False
        
        self.config = self.runner = self.server = self.pm = self.remote_runner = None
Пример #30
0
            logger.info('loading config file %s' % f)
            loader.load(f, config, verbose=verbose)
        except roslaunch.xmlloader.XmlParseException, e:
            raise RLException(e)
        except roslaunch.loader.LoadException, e:
            raise RLException(e)

    # we need this for the hardware test systems, which builds up
    # roslaunch launch files in memory
    if roslaunch_strs:
        for launch_str in roslaunch_strs:
            try:
                logger.info('loading config file from string')
                loader.load_string(launch_str, config)
            except roslaunch.xmlloader.XmlParseException, e:
                raise RLException('Launch string: %s\nException: %s' %
                                  (launch_str, e))
            except roslaunch.loader.LoadException, e:
                raise RLException('Launch string: %s\nException: %s' %
                                  (launch_str, e))

    if port:
        logger.info("overriding master port to %s" % port)
        config.master.set_port(port)

    # make sure our environment is correct
    config.validate()

    # choose machines for the nodes
    if assign_machines:
        config.assign_machines()
    return config