rosbridge_websocket.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2012, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of Willow Garage, Inc. nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 
34 from __future__ import print_function
35 import rospy
36 import sys
37 
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
42 import autobahn #to check version
43 from autobahn.twisted.websocket import WebSocketServerFactory, listenWS
44 from autobahn.websocket.compress import (PerMessageDeflateOffer,
45  PerMessageDeflateOfferAccept)
46 log.startLogging(sys.stdout)
47 
48 from rosbridge_server import ClientManager
49 from rosbridge_server.autobahn_websocket import RosbridgeWebSocket
50 from rosbridge_server.util import get_ephemeral_port
51 
52 from rosbridge_library.capabilities.advertise import Advertise
54 from rosbridge_library.capabilities.subscribe import Subscribe
55 from rosbridge_library.capabilities.advertise_service import AdvertiseService
56 from rosbridge_library.capabilities.unadvertise_service import UnadvertiseService
57 from rosbridge_library.capabilities.call_service import CallService
58 
59 
61  try:
62  reactor.stop()
63  except ReactorNotRunning:
64  rospy.logwarn("Can't stop the reactor, it wasn't running")
65 
66 
67 if __name__ == "__main__":
68  rospy.init_node("rosbridge_websocket")
69 
70  ##################################################
71  # Parameter handling #
72  ##################################################
73  retry_startup_delay = rospy.get_param('~retry_startup_delay', 2.0) # seconds
74 
75  use_compression = rospy.get_param('~use_compression', False)
76 
77  # get RosbridgeProtocol parameters
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)
87 
88  if RosbridgeWebSocket.max_message_size == "None":
89  RosbridgeWebSocket.max_message_size = None
90 
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) #default to original behaviour
94 
95  # SSL options
96  certfile = rospy.get_param('~certfile', None)
97  keyfile = rospy.get_param('~keyfile', None)
98  # if authentication should be used
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")
102 
103  external_port = int(rospy.get_param('~websocket_external_port', port))
104 
105  RosbridgeWebSocket.client_manager = ClientManager()
106 
107  # Get the glob strings and parse them as arrays.
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]
120 
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])
125  else:
126  print("--port argument provided without a value.")
127  sys.exit(-1)
128 
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])
133  else:
134  print("--address argument provided without a value.")
135  sys.exit(-1)
136 
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])
141  else:
142  print("--retry_startup_delay argument provided without a value.")
143  sys.exit(-1)
144 
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])
149  else:
150  print("--fragment_timeout argument provided without a value.")
151  sys.exit(-1)
152 
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])
157  else:
158  print("--delay_between_messages argument provided without a value.")
159  sys.exit(-1)
160 
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]
165  if value == "None":
166  RosbridgeWebSocket.max_message_size = None
167  else:
168  RosbridgeWebSocket.max_message_size = int(value)
169  else:
170  print("--max_message_size argument provided without a value. (can be None or <Integer>)")
171  sys.exit(-1)
172 
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])
177  else:
178  print("--unregister_timeout argument provided without a value.")
179  sys.exit(-1)
180 
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]
185  if value == "None":
186  RosbridgeWebSocket.topics_glob = []
187  else:
188  RosbridgeWebSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
189  else:
190  print("--topics_glob argument provided without a value. (can be None or a list)")
191  sys.exit(-1)
192 
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]
197  if value == "None":
198  RosbridgeWebSocket.services_glob = []
199  else:
200  RosbridgeWebSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
201  else:
202  print("--services_glob argument provided without a value. (can be None or a list)")
203  sys.exit(-1)
204 
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]
209  if value == "None":
210  RosbridgeWebSocket.params_glob = []
211  else:
212  RosbridgeWebSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
213  else:
214  print("--params_glob argument provided without a value. (can be None or a list)")
215  sys.exit(-1)
216 
217  if ("--bson_only_mode" in sys.argv) or bson_only_mode:
218  RosbridgeWebSocket.bson_only_mode = bson_only_mode
219 
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])
224  else:
225  print("--websocket_ping_interval argument provided without a value.")
226  sys.exit(-1)
227 
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])
232  else:
233  print("--websocket_ping_timeout argument provided without a value.")
234  sys.exit(-1)
235 
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])
240  else:
241  print("--websocket_external_port argument provided without a value.")
242  sys.exit(-1)
243 
244  # To be able to access the list of topics and services, you must be able to access the rosapi services.
245  if RosbridgeWebSocket.services_glob:
246  RosbridgeWebSocket.services_glob.append("/rosapi/*")
247 
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
254 
255  # Support the legacy "" address value.
256  # The socket library would interpret this as INADDR_ANY.
257  if not address:
258  address = '0.0.0.0'
259 
260  ##################################################
261  # Done with parameter handling #
262  ##################################################
263 
265  if not use_compression:
266  return
267  for offer in offers:
268  if isinstance(offer, PerMessageDeflateOffer):
269  return PerMessageDeflateOfferAccept(offer)
270 
271  if certfile is not None and keyfile is not None:
272  protocol = 'wss'
273  context_factory = ssl.DefaultOpenSSLContextFactory(keyfile, certfile)
274  else:
275  protocol = 'ws'
276  context_factory = None
277 
278  # For testing purposes, use an ephemeral port if port == 0.
279  if port == 0:
280  rospy.loginfo('Rosbridge WebSocket Picking an ephemeral port')
281  port = get_ephemeral_port()
282  # Write the actual port as a param for tests to read.
283  rospy.set_param('~actual_port', port)
284 
285  uri = '{}://{}:{}'.format(protocol, address, port)
286  factory = WebSocketServerFactory(uri, externalPort=external_port)
287  factory.protocol = RosbridgeWebSocket
288  # https://github.com/crossbario/autobahn-python/commit/2ef13a6804054de74eb36455b58a64a3c701f889
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,
294  )
295  else:
296  factory.setProtocolOptions(
297  perMessageCompressionAccept=handle_compression_offers,
298  autoPingInterval=ping_interval,
299  autoPingTimeout=ping_timeout,
300  allowNullOrigin=null_origin,
301  )
302 
303  connected = False
304  while not connected and not rospy.is_shutdown():
305  try:
306  listenWS(factory, context_factory)
307  rospy.loginfo('Rosbridge WebSocket server started at {}'.format(uri))
308  connected = True
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)
313 
314  rospy.on_shutdown(shutdown_hook)
315  reactor.run()
def get_ephemeral_port(sock_family=socket.AF_INET, sock_type=socket.SOCK_STREAM)
Definition: util.py:4
def handle_compression_offers(offers)
Done with parameter handling #.


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Wed Jun 3 2020 03:55:18