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 = int(rospy.get_param(
'~websocket_external_port', port))
105 RosbridgeWebSocket.client_manager = ClientManager()
108 RosbridgeWebSocket.topics_glob = [
109 element.strip().strip(
"'")
110 for element
in rospy.get_param(
'~topics_glob',
'')[1:-1].split(
',')
111 if len(element.strip().strip(
"'")) > 0]
112 RosbridgeWebSocket.services_glob = [
113 element.strip().strip(
"'")
114 for element
in rospy.get_param(
'~services_glob',
'')[1:-1].split(
',')
115 if len(element.strip().strip(
"'")) > 0]
116 RosbridgeWebSocket.params_glob = [
117 element.strip().strip(
"'")
118 for element
in rospy.get_param(
'~params_glob',
'')[1:-1].split(
',')
119 if len(element.strip().strip(
"'")) > 0]
121 if "--port" in sys.argv:
122 idx = sys.argv.index(
"--port")+1
123 if idx < len(sys.argv):
124 port = int(sys.argv[idx])
126 print(
"--port argument provided without a value.")
129 if "--address" in sys.argv:
130 idx = sys.argv.index(
"--address")+1
131 if idx < len(sys.argv):
132 address = str(sys.argv[idx])
134 print(
"--address argument provided without a value.")
137 if "--retry_startup_delay" in sys.argv:
138 idx = sys.argv.index(
"--retry_startup_delay") + 1
139 if idx < len(sys.argv):
140 retry_startup_delay = int(sys.argv[idx])
142 print(
"--retry_startup_delay argument provided without a value.")
145 if "--fragment_timeout" in sys.argv:
146 idx = sys.argv.index(
"--fragment_timeout") + 1
147 if idx < len(sys.argv):
148 RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx])
150 print(
"--fragment_timeout argument provided without a value.")
153 if "--delay_between_messages" in sys.argv:
154 idx = sys.argv.index(
"--delay_between_messages") + 1
155 if idx < len(sys.argv):
156 RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx])
158 print(
"--delay_between_messages argument provided without a value.")
161 if "--max_message_size" in sys.argv:
162 idx = sys.argv.index(
"--max_message_size") + 1
163 if idx < len(sys.argv):
164 value = sys.argv[idx]
166 RosbridgeWebSocket.max_message_size =
None 168 RosbridgeWebSocket.max_message_size = int(value)
170 print(
"--max_message_size argument provided without a value. (can be None or <Integer>)")
173 if "--unregister_timeout" in sys.argv:
174 idx = sys.argv.index(
"--unregister_timeout") + 1
175 if idx < len(sys.argv):
176 unregister_timeout = float(sys.argv[idx])
178 print(
"--unregister_timeout argument provided without a value.")
181 if "--topics_glob" in sys.argv:
182 idx = sys.argv.index(
"--topics_glob") + 1
183 if idx < len(sys.argv):
184 value = sys.argv[idx]
186 RosbridgeWebSocket.topics_glob = []
188 RosbridgeWebSocket.topics_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
190 print(
"--topics_glob argument provided without a value. (can be None or a list)")
193 if "--services_glob" in sys.argv:
194 idx = sys.argv.index(
"--services_glob") + 1
195 if idx < len(sys.argv):
196 value = sys.argv[idx]
198 RosbridgeWebSocket.services_glob = []
200 RosbridgeWebSocket.services_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
202 print(
"--services_glob argument provided without a value. (can be None or a list)")
205 if "--params_glob" in sys.argv:
206 idx = sys.argv.index(
"--params_glob") + 1
207 if idx < len(sys.argv):
208 value = sys.argv[idx]
210 RosbridgeWebSocket.params_glob = []
212 RosbridgeWebSocket.params_glob = [element.strip().strip(
"'")
for element
in value[1:-1].split(
',')]
214 print(
"--params_glob argument provided without a value. (can be None or a list)")
217 if (
"--bson_only_mode" in sys.argv)
or bson_only_mode:
218 RosbridgeWebSocket.bson_only_mode = bson_only_mode
220 if "--websocket_ping_interval" in sys.argv:
221 idx = sys.argv.index(
"--websocket_ping_interval") + 1
222 if idx < len(sys.argv):
223 ping_interval = float(sys.argv[idx])
225 print(
"--websocket_ping_interval argument provided without a value.")
228 if "--websocket_ping_timeout" in sys.argv:
229 idx = sys.argv.index(
"--websocket_ping_timeout") + 1
230 if idx < len(sys.argv):
231 ping_timeout = float(sys.argv[idx])
233 print(
"--websocket_ping_timeout argument provided without a value.")
236 if "--websocket_external_port" in sys.argv:
237 idx = sys.argv.index(
"--websocket_external_port") + 1
238 if idx < len(sys.argv):
239 external_port = int(sys.argv[idx])
241 print(
"--websocket_external_port argument provided without a value.")
245 if RosbridgeWebSocket.services_glob:
246 RosbridgeWebSocket.services_glob.append(
"/rosapi/*")
248 Subscribe.topics_glob = RosbridgeWebSocket.topics_glob
249 Advertise.topics_glob = RosbridgeWebSocket.topics_glob
250 Publish.topics_glob = RosbridgeWebSocket.topics_glob
251 AdvertiseService.services_glob = RosbridgeWebSocket.services_glob
252 UnadvertiseService.services_glob = RosbridgeWebSocket.services_glob
253 CallService.services_glob = RosbridgeWebSocket.services_glob
265 if not use_compression:
268 if isinstance(offer, PerMessageDeflateOffer):
269 return PerMessageDeflateOfferAccept(offer)
271 if certfile
is not None and keyfile
is not None:
273 context_factory = ssl.DefaultOpenSSLContextFactory(keyfile, certfile)
276 context_factory =
None 280 rospy.loginfo(
'Rosbridge WebSocket Picking an ephemeral port')
283 rospy.set_param(
'~actual_port', port)
285 uri =
'{}://{}:{}'.format(protocol, address, port)
286 factory = WebSocketServerFactory(uri, externalPort=external_port)
287 factory.protocol = RosbridgeWebSocket
289 if LooseVersion(autobahn.__version__) < LooseVersion(
"0.15.0"):
290 factory.setProtocolOptions(
291 perMessageCompressionAccept=handle_compression_offers,
292 autoPingInterval=ping_interval,
293 autoPingTimeout=ping_timeout,
296 factory.setProtocolOptions(
297 perMessageCompressionAccept=handle_compression_offers,
298 autoPingInterval=ping_interval,
299 autoPingTimeout=ping_timeout,
300 allowNullOrigin=null_origin,
304 while not connected
and not rospy.is_shutdown():
306 listenWS(factory, context_factory)
307 rospy.loginfo(
'Rosbridge WebSocket server started at {}'.format(uri))
309 except CannotListenError
as e:
310 rospy.logwarn(
"Unable to start server: " + str(e) +
311 " Retrying in " + str(retry_startup_delay) +
"s.")
312 rospy.sleep(retry_startup_delay)
314 rospy.on_shutdown(shutdown_hook)
def get_ephemeral_port(sock_family=socket.AF_INET, sock_type=socket.SOCK_STREAM)
def handle_compression_offers(offers)
Done with parameter handling #.