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 
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 = rospy.get_param('~websocket_external_port', None)
104  if external_port:
105  try:
106  external_port = int(external_port)
107  except ValueError:
108  external_port = None
109 
110  RosbridgeWebSocket.client_manager = ClientManager()
111 
112  # Get the glob strings and parse them as arrays.
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]
125 
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])
130  else:
131  print("--port argument provided without a value.")
132  sys.exit(-1)
133 
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])
138  else:
139  print("--address argument provided without a value.")
140  sys.exit(-1)
141 
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])
146  else:
147  print("--retry_startup_delay argument provided without a value.")
148  sys.exit(-1)
149 
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])
154  else:
155  print("--fragment_timeout argument provided without a value.")
156  sys.exit(-1)
157 
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])
162  else:
163  print("--delay_between_messages argument provided without a value.")
164  sys.exit(-1)
165 
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]
170  if value == "None":
171  RosbridgeWebSocket.max_message_size = None
172  else:
173  RosbridgeWebSocket.max_message_size = int(value)
174  else:
175  print("--max_message_size argument provided without a value. (can be None or <Integer>)")
176  sys.exit(-1)
177 
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])
182  else:
183  print("--unregister_timeout argument provided without a value.")
184  sys.exit(-1)
185 
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]
190  if value == "None":
191  RosbridgeWebSocket.topics_glob = []
192  else:
193  RosbridgeWebSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
194  else:
195  print("--topics_glob argument provided without a value. (can be None or a list)")
196  sys.exit(-1)
197 
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]
202  if value == "None":
203  RosbridgeWebSocket.services_glob = []
204  else:
205  RosbridgeWebSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
206  else:
207  print("--services_glob argument provided without a value. (can be None or a list)")
208  sys.exit(-1)
209 
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]
214  if value == "None":
215  RosbridgeWebSocket.params_glob = []
216  else:
217  RosbridgeWebSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')]
218  else:
219  print("--params_glob argument provided without a value. (can be None or a list)")
220  sys.exit(-1)
221 
222  if ("--bson_only_mode" in sys.argv) or bson_only_mode:
223  RosbridgeWebSocket.bson_only_mode = bson_only_mode
224 
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])
229  else:
230  print("--websocket_ping_interval argument provided without a value.")
231  sys.exit(-1)
232 
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])
237  else:
238  print("--websocket_ping_timeout argument provided without a value.")
239  sys.exit(-1)
240 
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])
245  else:
246  print("--websocket_external_port argument provided without a value.")
247  sys.exit(-1)
248 
249  # To be able to access the list of topics and services, you must be able to access the rosapi services.
250  if RosbridgeWebSocket.services_glob:
251  RosbridgeWebSocket.services_glob.append("/rosapi/*")
252 
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
259 
260  # Support the legacy "" address value.
261  # The socket library would interpret this as INADDR_ANY.
262  if not address:
263  address = '0.0.0.0'
264 
265 
268 
270  if not use_compression:
271  return
272  for offer in offers:
273  if isinstance(offer, PerMessageDeflateOffer):
274  return PerMessageDeflateOfferAccept(offer)
275 
276  if certfile is not None and keyfile is not None:
277  protocol = 'wss'
278  context_factory = ssl.DefaultOpenSSLContextFactory(keyfile, certfile)
279  else:
280  protocol = 'ws'
281  context_factory = None
282 
283  # For testing purposes, use an ephemeral port if port == 0.
284  if port == 0:
285  rospy.loginfo('Rosbridge WebSocket Picking an ephemeral port')
286  port = get_ephemeral_port()
287  # Write the actual port as a param for tests to read.
288  rospy.set_param('~actual_port', port)
289 
290  uri = '{}://{}:{}'.format(protocol, address, port)
291  factory = WebSocketServerFactory(uri, externalPort=external_port)
292  factory.protocol = RosbridgeWebSocket
293  # https://github.com/crossbario/autobahn-python/commit/2ef13a6804054de74eb36455b58a64a3c701f889
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,
299  )
300  else:
301  factory.setProtocolOptions(
302  perMessageCompressionAccept=handle_compression_offers,
303  autoPingInterval=ping_interval,
304  autoPingTimeout=ping_timeout,
305  allowNullOrigin=null_origin,
306  )
307 
308  connected = False
309  while not connected and not rospy.is_shutdown():
310  try:
311  listenWS(factory, context_factory)
312  rospy.loginfo('Rosbridge WebSocket server started at {}'.format(uri))
313  connected = True
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)
318 
319  rospy.on_shutdown(shutdown_hook)
320  reactor.run()
rosbridge_library::capabilities::call_service
rosbridge_server.util
Definition: util.py:1
rosbridge_server.autobahn_websocket
Definition: autobahn_websocket.py:1
rosbridge_server.util.get_ephemeral_port
def get_ephemeral_port(sock_family=socket.AF_INET, sock_type=socket.SOCK_STREAM)
Definition: util.py:4
rosbridge_library::capabilities::advertise_service
rosbridge_websocket.shutdown_hook
def shutdown_hook()
Definition: rosbridge_websocket.py:60
rosbridge_websocket.handle_compression_offers
def handle_compression_offers(offers)
Done with parameter handling #.
Definition: rosbridge_websocket.py:269
rosbridge_library::capabilities::unadvertise_service
rosbridge_library::capabilities::publish
rosbridge_library::capabilities::advertise
rosbridge_library::capabilities::subscribe


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Wed Feb 12 2025 03:14:56