34 from __future__
import print_function
38 from socket
import error
40 from tornado.ioloop
import IOLoop
41 from tornado.ioloop
import PeriodicCallback
42 from tornado.web
import Application
44 from rosbridge_server
import RosbridgeWebSocket, ClientManager
55 IOLoop.instance().stop()
57 if __name__ ==
"__main__":
58 rospy.init_node(
"rosbridge_websocket")
59 rospy.on_shutdown(shutdown_hook)
64 retry_startup_delay = rospy.get_param(
'~retry_startup_delay', 2.0)
66 RosbridgeWebSocket.use_compression = rospy.get_param(
'~use_compression',
False)
69 RosbridgeWebSocket.fragment_timeout = rospy.get_param(
'~fragment_timeout',
70 RosbridgeWebSocket.fragment_timeout)
71 RosbridgeWebSocket.delay_between_messages = rospy.get_param(
'~delay_between_messages',
72 RosbridgeWebSocket.delay_between_messages)
73 RosbridgeWebSocket.max_message_size = rospy.get_param(
'~max_message_size',
74 RosbridgeWebSocket.max_message_size)
75 RosbridgeWebSocket.unregister_timeout = rospy.get_param(
'~unregister_timeout',
76 RosbridgeWebSocket.unregister_timeout)
77 bson_only_mode = rospy.get_param(
'~bson_only_mode',
False)
79 if RosbridgeWebSocket.max_message_size ==
"None":
80 RosbridgeWebSocket.max_message_size =
None 83 certfile = rospy.get_param(
'~certfile',
None)
84 keyfile = rospy.get_param(
'~keyfile',
None)
86 RosbridgeWebSocket.authenticate = rospy.get_param(
'~authenticate',
False)
87 port = rospy.get_param(
'~port', 9090)
88 address = rospy.get_param(
'~address',
"")
90 RosbridgeWebSocket.client_manager = ClientManager()
93 RosbridgeWebSocket.topics_glob = [
94 element.strip().strip(
"'")
95 for element
in rospy.get_param(
'~topics_glob',
'')[1:-1].split(
',')
96 if len(element.strip().strip(
"'")) > 0]
97 RosbridgeWebSocket.services_glob = [
98 element.strip().strip(
"'")
99 for element
in rospy.get_param(
'~services_glob',
'')[1:-1].split(
',')
100 if len(element.strip().strip(
"'")) > 0]
101 RosbridgeWebSocket.params_glob = [
102 element.strip().strip(
"'")
103 for element
in rospy.get_param(
'~params_glob',
'')[1:-1].split(
',')
104 if len(element.strip().strip(
"'")) > 0]
106 if "--port" in sys.argv:
107 idx = sys.argv.index(
"--port")+1
108 if idx < len(sys.argv):
109 port = int(sys.argv[idx])
111 print(
"--port argument provided without a value.")
114 if "--address" in sys.argv:
115 idx = sys.argv.index(
"--address")+1
116 if idx < len(sys.argv):
117 address = int(sys.argv[idx])
119 print(
"--address argument provided without a value.")
122 if "--retry_startup_delay" in sys.argv:
123 idx = sys.argv.index(
"--retry_startup_delay") + 1
124 if idx < len(sys.argv):
125 retry_startup_delay = int(sys.argv[idx])
127 print(
"--retry_startup_delay argument provided without a value.")
130 if "--fragment_timeout" in sys.argv:
131 idx = sys.argv.index(
"--fragment_timeout") + 1
132 if idx < len(sys.argv):
133 RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx])
135 print(
"--fragment_timeout argument provided without a value.")
138 if "--delay_between_messages" in sys.argv:
139 idx = sys.argv.index(
"--delay_between_messages") + 1
140 if idx < len(sys.argv):
141 RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx])
143 print(
"--delay_between_messages argument provided without a value.")
146 if "--max_message_size" in sys.argv:
147 idx = sys.argv.index(
"--max_message_size") + 1
148 if idx < len(sys.argv):
149 value = sys.argv[idx]
151 RosbridgeWebSocket.max_message_size =
None 153 RosbridgeWebSocket.max_message_size = int(value)
155 print(
"--max_message_size argument provided without a value. (can be None or <Integer>)")
158 if "--unregister_timeout" in sys.argv:
159 idx = sys.argv.index(
"--unregister_timeout") + 1
160 if idx < len(sys.argv):
161 unregister_timeout = float(sys.argv[idx])
163 print(
"--unregister_timeout argument provided without a value.")
166 if "--topics_glob" in sys.argv:
167 idx = sys.argv.index(
"--topics_glob") + 1
168 if idx < len(sys.argv):
169 value = sys.argv[idx]
171 RosbridgeWebSocket.topics_glob = []
173 RosbridgeWebSocket.topics_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
175 print(
"--topics_glob argument provided without a value. (can be None or a list)")
178 if "--services_glob" in sys.argv:
179 idx = sys.argv.index(
"--services_glob") + 1
180 if idx < len(sys.argv):
181 value = sys.argv[idx]
183 RosbridgeWebSocket.services_glob = []
185 RosbridgeWebSocket.services_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
187 print(
"--services_glob argument provided without a value. (can be None or a list)")
190 if "--params_glob" in sys.argv:
191 idx = sys.argv.index(
"--params_glob") + 1
192 if idx < len(sys.argv):
193 value = sys.argv[idx]
195 RosbridgeWebSocket.params_glob = []
197 RosbridgeWebSocket.params_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
199 print(
"--params_glob argument provided without a value. (can be None or a list)")
202 if (
"--bson_only_mode" in sys.argv)
or bson_only_mode:
203 RosbridgeWebSocket.bson_only_mode = bson_only_mode
206 if RosbridgeWebSocket.services_glob:
207 RosbridgeWebSocket.services_glob.append(
"/rosapi/*")
209 Subscribe.topics_glob = RosbridgeWebSocket.topics_glob
210 Advertise.topics_glob = RosbridgeWebSocket.topics_glob
211 Publish.topics_glob = RosbridgeWebSocket.topics_glob
212 AdvertiseService.services_glob = RosbridgeWebSocket.services_glob
213 UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob
214 CallService.services_glob = RosbridgeWebSocket.services_glob
220 application = Application([(
r"/", RosbridgeWebSocket), (
r"", RosbridgeWebSocket)])
223 while not connected
and not rospy.is_shutdown():
225 if certfile
is not None and keyfile
is not None:
226 application.listen(port, address, ssl_options={
"certfile": certfile,
"keyfile": keyfile})
228 application.listen(port, address)
229 rospy.loginfo(
"Rosbridge WebSocket server started on port %d", port)
232 rospy.logwarn(
"Unable to start server: " + str(e) +
233 " Retrying in " + str(retry_startup_delay) +
"s.")
234 rospy.sleep(retry_startup_delay)
236 IOLoop.instance().start()