1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34 """
35 Internal use: rospy initialization.
36
37 This is mainly routines for initializing the master or slave based on
38 the OS environment.
39 """
40
41 import os
42 import sys
43 import logging
44 import time
45 import traceback
46
47 import rosgraph
48 import rosgraph.roslogging
49 import rosgraph.xmlrpc
50
51 from ..names import _set_caller_id
52 from ..core import is_shutdown, signal_shutdown, rospyerr
53
54 from .tcpros import init_tcpros
55 from .masterslave import ROSHandler
56
57 DEFAULT_NODE_PORT = 0
58 from rosgraph.rosenv import DEFAULT_MASTER_PORT
59 from rosgraph.rosenv import DEFAULT_MASTER_URI
60
61
62
63
65 """
66 If XML-RPC errors out of the run() method, this handler is invoked
67 """
68 rospyerr(traceback.format_exc())
69 signal_shutdown('error in XML-RPC server: %s'%(e))
70
71 -def start_node(environ, resolved_name, master_uri=None, port=0, tcpros_port=0):
72 """
73 Load ROS slave node, initialize from environment variables
74 @param environ: environment variables
75 @type environ: dict
76 @param resolved_name: resolved node name
77 @type resolved_name: str
78 @param master_uri: override ROS_MASTER_URI: XMlRPC URI of central ROS server
79 @type master_uri: str
80 @param port: override ROS_PORT: port of slave xml-rpc node
81 @type port: int
82 @param tcpros_port: override the port of the TCP server
83 @type tcpros_port: int
84 @return: node server instance
85 @rtype rosgraph.xmlrpc.XmlRpcNode
86 @raise ROSInitException: if node has already been started
87 """
88 init_tcpros(tcpros_port)
89 if not master_uri:
90 master_uri = rosgraph.get_master_uri()
91 if not master_uri:
92 master_uri = DEFAULT_MASTER_URI
93
94
95 _set_caller_id(resolved_name)
96
97 handler = ROSHandler(resolved_name, master_uri)
98 node = rosgraph.xmlrpc.XmlRpcNode(port, handler, on_run_error=_node_run_error)
99 node.start()
100 while not node.uri and not is_shutdown():
101 time.sleep(0.00001)
102 logging.getLogger("rospy.init").info("ROS Slave URI: [%s]", node.uri)
103
104 while not handler._is_registered() and not is_shutdown():
105 time.sleep(0.1)
106 logging.getLogger("rospy.init").info("registered with master")
107 return node
108
110 - def __init__(self, colorize=True, stdout=None, stderr=None):
112