3 from __future__
import print_function
4 from rospy
import init_node, get_param, loginfo, logerr, on_shutdown, Publisher
5 from rosbridge_server
import RosbridgeTcpSocket
14 from functools
import partial
15 from signal
import signal, SIGINT, SIG_DFL
16 from std_msgs.msg
import Int32
21 import socketserver
as SocketServer
34 if __name__ ==
"__main__":
39 print(
"trying to start rosbridge TCP server..")
42 init_node(
"rosbridge_tcp")
43 signal(SIGINT, SIG_DFL)
47 - try to get parameter from parameter server (..define those via launch-file) 48 - overwrite value if given as commandline-parameter 57 port = get_param(
'~port', 9090)
58 host = get_param(
'~host',
'')
59 incoming_buffer = get_param(
'~incoming_buffer', RosbridgeTcpSocket.incoming_buffer)
60 socket_timeout = get_param(
'~socket_timeout', RosbridgeTcpSocket.socket_timeout)
61 retry_startup_delay = get_param(
'~retry_startup_delay', 5.0)
62 fragment_timeout = get_param(
'~fragment_timeout', RosbridgeTcpSocket.fragment_timeout)
63 delay_between_messages = get_param(
'~delay_between_messages', RosbridgeTcpSocket.delay_between_messages)
64 max_message_size = get_param(
'~max_message_size', RosbridgeTcpSocket.max_message_size)
65 unregister_timeout = get_param(
'~unregister_timeout', RosbridgeTcpSocket.unregister_timeout)
66 bson_only_mode = get_param(
'~bson_only_mode',
False)
68 if max_message_size ==
"None":
69 max_message_size =
None 72 RosbridgeTcpSocket.topics_glob = [
73 element.strip().strip(
"'")
74 for element
in get_param(
'~topics_glob',
'')[1:-1].split(
',')
75 if len(element.strip().strip(
"'")) > 0]
76 RosbridgeTcpSocket.services_glob = [
77 element.strip().strip(
"'")
78 for element
in get_param(
'~services_glob',
'')[1:-1].split(
',')
79 if len(element.strip().strip(
"'")) > 0]
80 RosbridgeTcpSocket.params_glob = [
81 element.strip().strip(
"'")
82 for element
in get_param(
'~params_glob',
'')[1:-1].split(
',')
83 if len(element.strip().strip(
"'")) > 0]
86 RosbridgeTcpSocket.client_count_pub = Publisher(
'client_count', Int32, queue_size=10, latch=
True)
87 RosbridgeTcpSocket.client_count_pub.publish(0)
91 if "--port" in sys.argv:
92 idx = sys.argv.index(
"--port") + 1
93 if idx < len(sys.argv):
94 port = int(sys.argv[idx])
96 print(
"--port argument provided without a value.")
99 if "--host" in sys.argv:
100 idx = sys.argv.index(
"--host") + 1
101 if idx < len(sys.argv):
102 host = str(sys.argv[idx])
104 print(
"--host argument provided without a value.")
107 if "--incoming_buffer" in sys.argv:
108 idx = sys.argv.index(
"--incoming_buffer") + 1
109 if idx < len(sys.argv):
110 incoming_buffer = int(sys.argv[idx])
112 print(
"--incoming_buffer argument provided without a value.")
115 if "--socket_timeout" in sys.argv:
116 idx = sys.argv.index(
"--socket_timeout") + 1
117 if idx < len(sys.argv):
118 socket_timeout = int(sys.argv[idx])
120 print(
"--socket_timeout argument provided without a value.")
123 if "--retry_startup_delay" in sys.argv:
124 idx = sys.argv.index(
"--retry_startup_delay") + 1
125 if idx < len(sys.argv):
126 retry_startup_delay = int(sys.argv[idx])
128 print(
"--retry_startup_delay argument provided without a value.")
131 if "--fragment_timeout" in sys.argv:
132 idx = sys.argv.index(
"--fragment_timeout") + 1
133 if idx < len(sys.argv):
134 fragment_timeout = int(sys.argv[idx])
136 print(
"--fragment_timeout argument provided without a value.")
139 if "--delay_between_messages" in sys.argv:
140 idx = sys.argv.index(
"--delay_between_messages") + 1
141 if idx < len(sys.argv):
142 delay_between_messages = float(sys.argv[idx])
144 print(
"--delay_between_messages argument provided without a value.")
147 if "--max_message_size" in sys.argv:
148 idx = sys.argv.index(
"--max_message_size") + 1
149 if idx < len(sys.argv):
150 value = sys.argv[idx]
152 max_message_size =
None 154 max_message_size = int(value)
156 print(
"--max_message_size argument provided without a value. (can be None or <Integer>)")
159 if "--unregister_timeout" in sys.argv:
160 idx = sys.argv.index(
"--unregister_timeout") + 1
161 if idx < len(sys.argv):
162 unregister_timeout = float(sys.argv[idx])
164 print(
"--unregister_timeout argument provided without a value.")
168 RosbridgeTcpSocket.incoming_buffer = incoming_buffer
169 RosbridgeTcpSocket.socket_timeout = socket_timeout
170 RosbridgeTcpSocket.fragment_timeout = fragment_timeout
171 RosbridgeTcpSocket.delay_between_messages = delay_between_messages
172 RosbridgeTcpSocket.max_message_size = max_message_size
173 RosbridgeTcpSocket.unregister_timeout = unregister_timeout
174 RosbridgeTcpSocket.bson_only_mode = bson_only_mode
177 if "--topics_glob" in sys.argv:
178 idx = sys.argv.index(
"--topics_glob") + 1
179 if idx < len(sys.argv):
180 value = sys.argv[idx]
182 RosbridgeTcpSocket.topics_glob = []
184 RosbridgeTcpSocket.topics_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
186 print(
"--topics_glob argument provided without a value. (can be None or a list)")
189 if "--services_glob" in sys.argv:
190 idx = sys.argv.index(
"--services_glob") + 1
191 if idx < len(sys.argv):
192 value = sys.argv[idx]
194 RosbridgeTcpSocket.services_glob = []
196 RosbridgeTcpSocket.services_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
198 print(
"--services_glob argument provided without a value. (can be None or a list)")
201 if "--params_glob" in sys.argv:
202 idx = sys.argv.index(
"--params_glob") + 1
203 if idx < len(sys.argv):
204 value = sys.argv[idx]
206 RosbridgeTcpSocket.params_glob = []
208 RosbridgeTcpSocket.params_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
210 print(
"--params_glob argument provided without a value. (can be None or a list)")
213 if "--bson_only_mode" in sys.argv:
214 bson_only_mode =
True 217 if RosbridgeTcpSocket.services_glob:
218 RosbridgeTcpSocket.services_glob.append(
"/rosapi/*")
220 Subscribe.topics_glob = RosbridgeTcpSocket.topics_glob
221 Advertise.topics_glob = RosbridgeTcpSocket.topics_glob
222 Publish.topics_glob = RosbridgeTcpSocket.topics_glob
223 AdvertiseService.services_glob = RosbridgeTcpSocket.services_glob
224 UnadvertiseService.services_glob = RosbridgeTcpSocket.services_glob
225 CallService.services_glob = RosbridgeTcpSocket.services_glob
228 ...END (parameter handling) 234 SocketServer.ThreadingTCPServer.allow_reuse_address =
True 235 server = SocketServer.ThreadingTCPServer((host, port), RosbridgeTcpSocket)
236 on_shutdown(partial(shutdown_hook, server))
238 loginfo(
"Rosbridge TCP server started on port %d", port)
240 server.serve_forever()
242 except Exception
as e:
243 time.sleep(retry_startup_delay)
244 print(
"server loaded")
def shutdown_hook(server)