예제 #1
0
    def launch_node(self, node, core=False):

        # if core == True:
        #     import roslaunch.core
        #     import rosmaster.registration_logger
        #     m = roslaunch.core.Master()
        #     print(m.is_running())
        #     if m.is_running():
        #         rosmaster.registration_logger.addLogger('roslaunch')
        """
        Launch a single node locally. Remote launching is handled separately by the remote module.
        If node name is not assigned, one will be created for it.
        
        @param node Node: node to launch
        @param core bool: if True, core node
        @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
        """
        self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type)

        # TODO: should this always override, per spec?. I added this
        # so that this api can be called w/o having to go through an
        # extra assign machines step.
        if node.machine is None:
            node.machine = self.config.machines['']
        if node.name is None:
            node.name = rosgraph.names.anonymous_name(node.type)
            
        master = self.config.master
        import roslaunch.node_args
        try:
            process = create_node_process(self.run_id, node, master.uri)
        except roslaunch.node_args.NodeParamsException as e:
            self.logger.error(e)
            if node.package == 'rosout' and node.type == 'rosout':
                printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n")
            else:
                printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e)))
            if node.name:
                return node.name, False
            else:
                return "%s/%s"%(node.package,node.type), False                

        self.logger.info("... created process [%s]", process.name)
        if core:
            self.pm.register_core_proc(process)
        else:
            self.pm.register(process)            
        node.process_name = process.name #store this in the node object for easy reference
        self.logger.info("... registered process [%s]", process.name)

        # note: this may raise FatalProcessLaunch, which aborts the entire launch
        success = process.start()
        if not success:
            if node.machine.name:
                printerrlog("launch of %s/%s on %s failed"%(node.package, node.type, node.machine.name))
            else:
                printerrlog("local launch of %s/%s failed"%(node.package, node.type))   
        else:
            self.logger.info("... successfully launched [%s]", process.name)
        return process, success
예제 #2
0
 def launch_node(self, config, node, core=False):
     """
     Launch a single node locally. Remote launching is handled separately by the remote module.
     If node name is not assigned, one will be created for it.
     
     @param node Node: node to launch
     @param core bool: if True, core node
     @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
     """
     self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type)
     
     # TODO: should this always override, per spec?. I added this
     # so that this api can be called w/o having to go through an
     # extra assign machines step.
     if node.machine is None:
         node.machine = config.machines['']
     if node.name is None:
         node.name = roslib.names.anonymous_name(node.type)
         
     master = config.master
     import roslaunch.node_args
     try:
         process = create_node_process(self.run_id, node, master.uri)
     except roslaunch.node_args.NodeParamsException, e:
         self.logger.error(e)
         if node.package == 'rosout' and node.type == 'rosout':
             printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n")
         else:
             printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e)))
         if node.name:
             return node.name, False
         else:
             return "%s/%s"%(node.package,node.type), False                
예제 #3
0
 def recreate_process(self):
     """
     Create and set roslaunch.nodeprocess.LocalProcess to member variable.
     @rtype: roslaunch.nodeprocess.LocalProcess
     """
     return nodeprocess.create_node_process(self._run_id, self.config,
                                            self.master_uri)
예제 #4
0
파일: launch.py 프로젝트: lucasw/ros_comm-1
 def launch_node(self, node, core=False):
     """
     Launch a single node locally. Remote launching is handled separately by the remote module.
     If node name is not assigned, one will be created for it.
     
     @param node Node: node to launch
     @param core bool: if True, core node
     @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
     """
     self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type)
     
     # TODO: should this always override, per spec?. I added this
     # so that this api can be called w/o having to go through an
     # extra assign machines step.
     if node.machine is None:
         node.machine = self.config.machines['']
     if node.name is None:
         node.name = roslib.names.anonymous_name(node.type)
         
     master = self.config.master
     import roslaunch.node_args
     try:
         process = create_node_process(self.run_id, node, master.uri)
     except roslaunch.node_args.NodeParamsException, e:
         self.logger.error(e)
         if node.package == 'rosout' and node.type == 'rosout':
             printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n")
         else:
             printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e)))
         if node.name:
             return node.name, False
         else:
             return "%s/%s"%(node.package,node.type), False                
예제 #5
0
    def launch_node(self, node, core=False):
        """
        Launch a single node locally. Remote launching is handled separately by the remote module.
        If node name is not assigned, one will be created for it.
        
        @param node Node: node to launch
        @param core bool: if True, core node
        @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
        """
        self.logger.info("... preparing to launch node of type [%s/%s]",
                         node.package, node.type)

        # TODO: should this always override, per spec?. I added this
        # so that this api can be called w/o having to go through an
        # extra assign machines step.
        if node.machine is None:
            node.machine = self.config.machines['']
        if node.name is None:
            node.name = rosgraph.names.anonymous_name(node.type)

        master = self.config.master
        import roslaunch.node_args
        try:
            process = create_node_process(self.run_id, node, master.uri)
        except roslaunch.node_args.NodeParamsException as e:
            self.logger.error(e)
            if node.package == 'rosout' and node.type == 'rosout':
                printerrlog(
                    "\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n"
                )
            else:
                printerrlog("ERROR: cannot launch node of type [%s/%s]: %s" %
                            (node.package, node.type, str(e)))
            if node.name:
                return node.name, False
            else:
                return "%s/%s" % (node.package, node.type), False

        self.logger.info("... created process [%s]", process.name)
        if core:
            self.pm.register_core_proc(process)
        else:
            self.pm.register(process)
        node.process_name = process.name  #store this in the node object for easy reference
        self.logger.info("... registered process [%s]", process.name)

        # note: this may raise FatalProcessLaunch, which aborts the entire launch
        success = process.start()
        if not success:
            if node.machine.name:
                printerrlog("launch of %s/%s on %s failed" %
                            (node.package, node.type, node.machine.name))
            else:
                printerrlog("local launch of %s/%s failed" %
                            (node.package, node.type))
        else:
            self.logger.info("... successfully launched [%s]", process.name)
        return process, success
예제 #6
0
    def check_stop_timeouts(self, master_uri, n, run_id, sigint_timeout,
                            sigterm_timeout):
        from roslaunch.nodeprocess import create_node_process, LocalProcess

        import time
        import tempfile
        import signal

        signal_log_file = os.path.join(tempfile.gettempdir(), "signal.log")

        try:
            os.remove(signal_log_file)
        except OSError:
            pass

        p = create_node_process(run_id,
                                n,
                                master_uri,
                                sigint_timeout=sigint_timeout,
                                sigterm_timeout=sigterm_timeout)
        self.assert_(isinstance(p, LocalProcess))

        p.start()
        time.sleep(3)  # give it time to start

        before_stop_call_time = time.time()
        p.stop()
        after_stop_call_time = time.time()

        signals = dict()

        try:
            with open(signal_log_file, 'r') as f:
                lines = f.readlines()
                for line in lines:
                    sig, timestamp = line.split(" ")
                    sig = int(sig)
                    timestamp = float(timestamp)
                    signals[sig] = timestamp
        except IOError:
            self.fail("Could not open %s" % signal_log_file)

        self.assertSetEqual({signal.SIGINT, signal.SIGTERM},
                            set(signals.keys()))
        self.assertAlmostEqual(before_stop_call_time,
                               signals[signal.SIGINT],
                               delta=1)
        self.assertAlmostEqual(before_stop_call_time,
                               signals[signal.SIGTERM] - sigint_timeout,
                               delta=1)
        self.assertAlmostEqual(before_stop_call_time,
                               after_stop_call_time - sigint_timeout -
                               sigterm_timeout,
                               delta=1)
예제 #7
0
    def recreate_process(self):
        '''
        Create and set roslaunch.nodeprocess.LocalProcess to member variable.
        @rtype: roslaunch.nodeprocess.LocalProcess
        '''
        _local_process = nodeprocess.LocalProcess
        try:
            _local_process = nodeprocess.create_node_process(
                self._run_id, self.config, self.master_uri)
        except node_args.NodeParamsException as e:
            rospy.logerr('roslaunch failed to load the node. {}'.format(
                e.message))
            # TODO: Show msg on GUI that the node wasn't loaded.

        return _local_process
예제 #8
0
    def recreate_process(self):
        '''
        Create and set roslaunch.nodeprocess.LocalProcess to member variable.
        @rtype: roslaunch.nodeprocess.LocalProcess
        '''
        _local_process = nodeprocess.LocalProcess
        try:
            _local_process = nodeprocess.create_node_process(
                                    self._run_id, self.config, self.master_uri)
        except node_args.NodeParamsException as e:
            rospy.logerr('roslaunch failed to load the node. {}'.format(
                                                                   e.message))
            #TODO: Show msg on GUI that the node wasn't loaded.

        return _local_process
예제 #9
0
    def test_create_node_process(self):
        from roslaunch.core import Node, Machine, RLException
        from roslaunch.node_args import NodeParamsException
        from roslaunch.nodeprocess import create_node_process, LocalProcess
        # have to use real ROS configuration for these tests
        ros_root = os.environ['ROS_ROOT']
        rpp = os.environ.get('ROS_PACKAGE_PATH', None)
        master_uri = 'http://masteruri:1234'
        m = Machine('name1', ros_root, rpp, '1.2.3.4')

        run_id = 'id'
        
        # test invalid params
        n = Node('not_a_real_package','not_a_node')
        n.machine = m
        n.name = 'foo'
        try: # should fail b/c node cannot be found
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except NodeParamsException:
            pass
        
        # have to specify a real node
        n = Node('rospy','talker.py')
        n.machine = m
        try: # should fail b/c n.name is not set
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except ValueError:
            pass
        
        # have to specify a real node
        n = Node('rospy','talker.py')

        n.machine = None
        n.name = 'talker'
        try: # should fail b/c n.machine is not set
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except RLException:
            pass

        # basic integration test
        n.machine = m
        p = create_node_process(run_id, n, master_uri)
        self.assert_(isinstance(p, LocalProcess))

        # repeat some setup_local_process_env tests
        d = p.env
        self.assertEquals(d['ROS_MASTER_URI'], master_uri)
        self.assertEquals(d['ROS_ROOT'], ros_root)
        self.assertEquals(d['PYTHONPATH'], os.environ['PYTHONPATH'])
        if rpp:
            self.assertEquals(d['ROS_PACKAGE_PATH'], rpp)
        for k in ['ROS_IP', 'ROS_NAMESPACE']:
            if k in d:
                self.fail('%s should not be set: %s'%(k,d[k]))

        # test package and name
        self.assertEquals(p.package, 'rospy')
        # - no 'correct' full answer here 
        self.assert_(p.name.startswith('talker'), p.name)

        # test log_output
        n.output = 'log'
        self.assert_(create_node_process(run_id, n, master_uri).log_output)
        n.output = 'screen'
        self.failIf(create_node_process(run_id, n, master_uri).log_output)

        # test respawn
        n.respawn = True
        self.assert_(create_node_process(run_id, n, master_uri).respawn)
        n.respawn = False
        self.failIf(create_node_process(run_id, n, master_uri).respawn)        

        # test cwd
        n.cwd = None
        self.assertEquals(create_node_process(run_id, n, master_uri).cwd, None)
        n.cwd = 'ros-root'
        self.assertEquals(create_node_process(run_id, n, master_uri).cwd, 'ros-root')
        n.cwd = 'node'                
        self.assertEquals(create_node_process(run_id, n, master_uri).cwd, 'node')

        # test args

        # - simplest test (no args)
        n.args = ''
        p = create_node_process(run_id, n, master_uri)
        # - the first arg should be the path to the node executable
        rospack = rospkg.RosPack()
        cmd = roslib.packages.find_node('rospy', 'talker.py', rospack)[0]
        self.assertEquals(p.args[0], cmd)

        # - test basic args
        n.args = "arg1 arg2 arg3"
        p = create_node_process(run_id, n, master_uri)
        self.assertEquals(p.args[0], cmd)
        for a in "arg1 arg2 arg3".split():
            self.assert_(a in p.args)
            
        # - test remap args
        n.remap_args = [('KEY1', 'VAL1'), ('KEY2', 'VAL2')]
        p = create_node_process(run_id, n, master_uri)
        self.assert_('KEY1:=VAL1' in p.args)        
        self.assert_('KEY2:=VAL2' in p.args)
        
        # - test __name
        n = Node('rospy','talker.py')
        n.name = 'fooname'
        n.machine = m
        self.assert_('__name:=fooname' in create_node_process(run_id, n, master_uri).args)
        
        # - test substitution args
        os.environ['SUB_TEST'] = 'subtest'
        os.environ['SUB_TEST2'] = 'subtest2'
        n.args = 'foo $(env SUB_TEST) $(env SUB_TEST2)'
        p = create_node_process(run_id, n, master_uri)        
        self.failIf('SUB_TEST' in p.args)
        self.assert_('foo' in p.args)
        self.assert_('subtest' in p.args)
        self.assert_('subtest2' in p.args)        
예제 #10
0
    def test_create_node_process(self):
        from roslaunch.core import Node, Machine, RLException
        from roslaunch.node_args import NodeParamsException
        from roslaunch.nodeprocess import create_node_process, LocalProcess
        # have to use real ROS configuration for these tests
        ros_root = os.environ['ROS_ROOT']
        rpp = os.environ.get('ROS_PACKAGE_PATH', None)
        master_uri = 'http://masteruri:1234'
        m = Machine('name1', ros_root, rpp, '1.2.3.4')

        run_id = 'id'

        # test invalid params
        n = Node('not_a_real_package', 'not_a_node')
        n.machine = m
        n.name = 'foo'
        try:  # should fail b/c node cannot be found
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except NodeParamsException:
            pass

        # have to specify a real node
        n = Node('roslaunch', 'talker.py')
        n.machine = m
        try:  # should fail b/c n.name is not set
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except ValueError:
            pass

        # have to specify a real node
        n = Node('roslaunch', 'talker.py')

        n.machine = None
        n.name = 'talker'
        try:  # should fail b/c n.machine is not set
            create_node_process(run_id, n, master_uri)
            self.fail("should have failed")
        except RLException:
            pass

        # basic integration test
        n.machine = m
        p = create_node_process(run_id, n, master_uri)
        self.assert_(isinstance(p, LocalProcess))

        # repeat some setup_local_process_env tests
        d = p.env
        self.assertEquals(d['ROS_MASTER_URI'], master_uri)
        self.assertEquals(d['ROS_ROOT'], ros_root)
        self.assertEquals(d['PYTHONPATH'], os.environ['PYTHONPATH'])
        if rpp:
            self.assertEquals(d['ROS_PACKAGE_PATH'], rpp)
        for k in ['ROS_IP', 'ROS_NAMESPACE']:
            if k in d:
                self.fail('%s should not be set: %s' % (k, d[k]))

        # test package and name
        self.assertEquals(p.package, 'roslaunch')
        # - no 'correct' full answer here
        self.assert_(p.name.startswith('talker'), p.name)

        # test log_output
        n.output = 'log'
        self.assert_(create_node_process(run_id, n, master_uri).log_output)
        n.output = 'screen'
        self.failIf(create_node_process(run_id, n, master_uri).log_output)

        # test respawn
        n.respawn = True
        self.assert_(create_node_process(run_id, n, master_uri).respawn)
        n.respawn = False
        self.failIf(create_node_process(run_id, n, master_uri).respawn)

        # test cwd
        n.cwd = None
        self.assertEquals(create_node_process(run_id, n, master_uri).cwd, None)
        n.cwd = 'ros-root'
        self.assertEquals(
            create_node_process(run_id, n, master_uri).cwd, 'ros-root')
        n.cwd = 'node'
        self.assertEquals(
            create_node_process(run_id, n, master_uri).cwd, 'node')

        # sigint timeout
        self.assertEquals(
            create_node_process(run_id, n, master_uri).sigint_timeout, 15)
        self.assertEquals(
            create_node_process(run_id, n, master_uri,
                                sigint_timeout=1).sigint_timeout, 1)
        self.assertRaises(RLException,
                          create_node_process,
                          run_id,
                          n,
                          master_uri,
                          sigint_timeout=0)

        # sigterm timeout
        self.assertEquals(
            create_node_process(run_id, n, master_uri).sigterm_timeout, 2)
        self.assertEquals(
            create_node_process(run_id, n, master_uri,
                                sigterm_timeout=1).sigterm_timeout, 1)
        self.assertRaises(RLException,
                          create_node_process,
                          run_id,
                          n,
                          master_uri,
                          sigterm_timeout=0)

        # test args

        # - simplest test (no args)
        n.args = ''
        p = create_node_process(run_id, n, master_uri)
        # - the first arg should be the path to the node executable
        rospack = rospkg.RosPack()
        cmd = roslib.packages.find_node('roslaunch', 'talker.py', rospack)[0]
        self.assertEquals(p.args[0], cmd)

        # - test basic args
        n.args = "arg1 arg2 arg3"
        p = create_node_process(run_id, n, master_uri)
        self.assertEquals(p.args[0], cmd)
        for a in "arg1 arg2 arg3".split():
            self.assert_(a in p.args)

        # - test remap args
        n.remap_args = [('KEY1', 'VAL1'), ('KEY2', 'VAL2')]
        p = create_node_process(run_id, n, master_uri)
        self.assert_('KEY1:=VAL1' in p.args)
        self.assert_('KEY2:=VAL2' in p.args)

        # - test __name
        n = Node('roslaunch', 'talker.py')
        n.name = 'fooname'
        n.machine = m
        self.assert_('__name:=fooname' in create_node_process(
            run_id, n, master_uri).args)

        # - test substitution args
        os.environ['SUB_TEST'] = 'subtest'
        os.environ['SUB_TEST2'] = 'subtest2'
        n.args = 'foo $(env SUB_TEST) $(env SUB_TEST2)'
        p = create_node_process(run_id, n, master_uri)
        self.failIf('SUB_TEST' in p.args)
        self.assert_('foo' in p.args)
        self.assert_('subtest' in p.args)
        self.assert_('subtest2' in p.args)