34 from __future__
import print_function
38 from twisted.python
import log
39 from twisted.internet
import reactor, ssl
40 from twisted.internet.error
import CannotListenError, ReactorNotRunning
41 from distutils.version
import LooseVersion
43 from autobahn.twisted.websocket
import WebSocketServerFactory, listenWS
44 from autobahn.websocket.compress
import (PerMessageDeflateOffer,
45 PerMessageDeflateOfferAccept)
46 log.startLogging(sys.stdout)
48 from rosbridge_server
import ClientManager
63 except ReactorNotRunning:
64 rospy.logwarn(
"Can't stop the reactor, it wasn't running")
67 if __name__ ==
"__main__":
68 rospy.init_node(
"rosbridge_websocket")
73 retry_startup_delay = rospy.get_param(
'~retry_startup_delay', 2.0)
75 use_compression = rospy.get_param(
'~use_compression',
False)
78 RosbridgeWebSocket.fragment_timeout = rospy.get_param(
'~fragment_timeout',
79 RosbridgeWebSocket.fragment_timeout)
80 RosbridgeWebSocket.delay_between_messages = rospy.get_param(
'~delay_between_messages',
81 RosbridgeWebSocket.delay_between_messages)
82 RosbridgeWebSocket.max_message_size = rospy.get_param(
'~max_message_size',
83 RosbridgeWebSocket.max_message_size)
84 RosbridgeWebSocket.unregister_timeout = rospy.get_param(
'~unregister_timeout',
85 RosbridgeWebSocket.unregister_timeout)
86 bson_only_mode = rospy.get_param(
'~bson_only_mode',
False)
88 if RosbridgeWebSocket.max_message_size ==
"None":
89 RosbridgeWebSocket.max_message_size =
None
91 ping_interval = float(rospy.get_param(
'~websocket_ping_interval', 0))
92 ping_timeout = float(rospy.get_param(
'~websocket_ping_timeout', 30))
93 null_origin = rospy.get_param(
'~websocket_null_origin',
True)
96 certfile = rospy.get_param(
'~certfile',
None)
97 keyfile = rospy.get_param(
'~keyfile',
None)
99 RosbridgeWebSocket.authenticate = rospy.get_param(
'~authenticate',
False)
100 port = rospy.get_param(
'~port', 9090)
101 address = rospy.get_param(
'~address',
"0.0.0.0")
103 external_port = rospy.get_param(
'~websocket_external_port',
None)
106 external_port = int(external_port)
110 RosbridgeWebSocket.client_manager = ClientManager()
113 RosbridgeWebSocket.topics_glob = [
114 element.strip().strip(
"'")
115 for element
in rospy.get_param(
'~topics_glob',
'')[1:-1].split(
',')
116 if len(element.strip().strip(
"'")) > 0]
117 RosbridgeWebSocket.services_glob = [
118 element.strip().strip(
"'")
119 for element
in rospy.get_param(
'~services_glob',
'')[1:-1].split(
',')
120 if len(element.strip().strip(
"'")) > 0]
121 RosbridgeWebSocket.params_glob = [
122 element.strip().strip(
"'")
123 for element
in rospy.get_param(
'~params_glob',
'')[1:-1].split(
',')
124 if len(element.strip().strip(
"'")) > 0]
126 if "--port" in sys.argv:
127 idx = sys.argv.index(
"--port")+1
128 if idx < len(sys.argv):
129 port = int(sys.argv[idx])
131 print(
"--port argument provided without a value.")
134 if "--address" in sys.argv:
135 idx = sys.argv.index(
"--address")+1
136 if idx < len(sys.argv):
137 address = str(sys.argv[idx])
139 print(
"--address argument provided without a value.")
142 if "--retry_startup_delay" in sys.argv:
143 idx = sys.argv.index(
"--retry_startup_delay") + 1
144 if idx < len(sys.argv):
145 retry_startup_delay = int(sys.argv[idx])
147 print(
"--retry_startup_delay argument provided without a value.")
150 if "--fragment_timeout" in sys.argv:
151 idx = sys.argv.index(
"--fragment_timeout") + 1
152 if idx < len(sys.argv):
153 RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx])
155 print(
"--fragment_timeout argument provided without a value.")
158 if "--delay_between_messages" in sys.argv:
159 idx = sys.argv.index(
"--delay_between_messages") + 1
160 if idx < len(sys.argv):
161 RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx])
163 print(
"--delay_between_messages argument provided without a value.")
166 if "--max_message_size" in sys.argv:
167 idx = sys.argv.index(
"--max_message_size") + 1
168 if idx < len(sys.argv):
169 value = sys.argv[idx]
171 RosbridgeWebSocket.max_message_size =
None
173 RosbridgeWebSocket.max_message_size = int(value)
175 print(
"--max_message_size argument provided without a value. (can be None or <Integer>)")
178 if "--unregister_timeout" in sys.argv:
179 idx = sys.argv.index(
"--unregister_timeout") + 1
180 if idx < len(sys.argv):
181 unregister_timeout = float(sys.argv[idx])
183 print(
"--unregister_timeout argument provided without a value.")
186 if "--topics_glob" in sys.argv:
187 idx = sys.argv.index(
"--topics_glob") + 1
188 if idx < len(sys.argv):
189 value = sys.argv[idx]
191 RosbridgeWebSocket.topics_glob = []
193 RosbridgeWebSocket.topics_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
195 print(
"--topics_glob argument provided without a value. (can be None or a list)")
198 if "--services_glob" in sys.argv:
199 idx = sys.argv.index(
"--services_glob") + 1
200 if idx < len(sys.argv):
201 value = sys.argv[idx]
203 RosbridgeWebSocket.services_glob = []
205 RosbridgeWebSocket.services_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
207 print(
"--services_glob argument provided without a value. (can be None or a list)")
210 if "--params_glob" in sys.argv:
211 idx = sys.argv.index(
"--params_glob") + 1
212 if idx < len(sys.argv):
213 value = sys.argv[idx]
215 RosbridgeWebSocket.params_glob = []
217 RosbridgeWebSocket.params_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
219 print(
"--params_glob argument provided without a value. (can be None or a list)")
222 if (
"--bson_only_mode" in sys.argv)
or bson_only_mode:
223 RosbridgeWebSocket.bson_only_mode = bson_only_mode
225 if "--websocket_ping_interval" in sys.argv:
226 idx = sys.argv.index(
"--websocket_ping_interval") + 1
227 if idx < len(sys.argv):
228 ping_interval = float(sys.argv[idx])
230 print(
"--websocket_ping_interval argument provided without a value.")
233 if "--websocket_ping_timeout" in sys.argv:
234 idx = sys.argv.index(
"--websocket_ping_timeout") + 1
235 if idx < len(sys.argv):
236 ping_timeout = float(sys.argv[idx])
238 print(
"--websocket_ping_timeout argument provided without a value.")
241 if "--websocket_external_port" in sys.argv:
242 idx = sys.argv.index(
"--websocket_external_port") + 1
243 if idx < len(sys.argv):
244 external_port = int(sys.argv[idx])
246 print(
"--websocket_external_port argument provided without a value.")
250 if RosbridgeWebSocket.services_glob:
251 RosbridgeWebSocket.services_glob.append(
"/rosapi/*")
253 Subscribe.topics_glob = RosbridgeWebSocket.topics_glob
254 Advertise.topics_glob = RosbridgeWebSocket.topics_glob
255 Publish.topics_glob = RosbridgeWebSocket.topics_glob
256 AdvertiseService.services_glob = RosbridgeWebSocket.services_glob
257 UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob
258 CallService.services_glob = RosbridgeWebSocket.services_glob
270 if not use_compression:
273 if isinstance(offer, PerMessageDeflateOffer):
274 return PerMessageDeflateOfferAccept(offer)
276 if certfile
is not None and keyfile
is not None:
278 context_factory = ssl.DefaultOpenSSLContextFactory(keyfile, certfile)
281 context_factory =
None
285 rospy.loginfo(
'Rosbridge WebSocket Picking an ephemeral port')
288 rospy.set_param(
'~actual_port', port)
290 uri =
'{}://{}:{}'.format(protocol, address, port)
291 factory = WebSocketServerFactory(uri, externalPort=external_port)
292 factory.protocol = RosbridgeWebSocket
294 if LooseVersion(autobahn.__version__) < LooseVersion(
"0.15.0"):
295 factory.setProtocolOptions(
296 perMessageCompressionAccept=handle_compression_offers,
297 autoPingInterval=ping_interval,
298 autoPingTimeout=ping_timeout,
301 factory.setProtocolOptions(
302 perMessageCompressionAccept=handle_compression_offers,
303 autoPingInterval=ping_interval,
304 autoPingTimeout=ping_timeout,
305 allowNullOrigin=null_origin,
309 while not connected
and not rospy.is_shutdown():
311 listenWS(factory, context_factory)
312 rospy.loginfo(
'Rosbridge WebSocket server started at {}'.format(uri))
314 except CannotListenError
as e:
315 rospy.logwarn(
"Unable to start server: " + str(e) +
316 " Retrying in " + str(retry_startup_delay) +
"s.")
317 rospy.sleep(retry_startup_delay)
319 rospy.on_shutdown(shutdown_hook)