websocket_handler.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import rospy
34 import uuid
35 
36 from rosauth.srv import Authentication
37 
38 import sys
39 import threading
40 import traceback
41 from functools import partial, wraps
42 
43 from tornado import version_info as tornado_version_info
44 from tornado.ioloop import IOLoop
45 from tornado.iostream import StreamClosedError
46 from tornado.websocket import WebSocketHandler, WebSocketClosedError
47 from tornado.gen import coroutine, BadYieldError
48 
49 from rosbridge_library.rosbridge_protocol import RosbridgeProtocol
50 from rosbridge_library.util import json, bson
51 
52 
54  """Log the most recent exception to ROS."""
55  exc = traceback.format_exception(*sys.exc_info())
56  rospy.logerr(''.join(exc))
57 
58 
60  """Decorator for logging exceptions to ROS."""
61  @wraps(f)
62  def wrapper(*args, **kwargs):
63  try:
64  return f(*args, **kwargs)
65  except:
67  raise
68  return wrapper
69 
70 
71 class RosbridgeWebSocket(WebSocketHandler):
72  client_id_seed = 0
73  clients_connected = 0
74  authenticate = False
75  use_compression = False
76 
77  # The following are passed on to RosbridgeProtocol
78  # defragmentation.py:
79  fragment_timeout = 600 # seconds
80  # protocol.py:
81  delay_between_messages = 0 # seconds
82  max_message_size = None # bytes
83  unregister_timeout = 10.0 # seconds
84  bson_only_mode = False
85 
86  @log_exceptions
87  def open(self):
88  rospy.logwarn_once('The Tornado Rosbridge WebSocket implementation is deprecated.'
89  ' See rosbridge_server.autobahn_websocket'
90  ' and rosbridge_websocket.py')
91  cls = self.__class__
92  parameters = {
93  "fragment_timeout": cls.fragment_timeout,
94  "delay_between_messages": cls.delay_between_messages,
95  "max_message_size": cls.max_message_size,
96  "unregister_timeout": cls.unregister_timeout,
97  "bson_only_mode": cls.bson_only_mode
98  }
99  try:
100  self.protocol = RosbridgeProtocol(cls.client_id_seed, parameters=parameters)
101  self.protocol.outgoing = self.send_message
102  self.set_nodelay(True)
103  self.authenticated = False
104  self._write_lock = threading.RLock()
105  cls.client_id_seed += 1
106  cls.clients_connected += 1
107  self.client_id = uuid.uuid4()
108  if cls.client_manager:
109  cls.client_manager.add_client(self.client_id, self.request.remote_ip)
110  except Exception as exc:
111  rospy.logerr("Unable to accept incoming connection. Reason: %s", str(exc))
112  rospy.loginfo("Client connected. %d clients total.", cls.clients_connected)
113  if cls.authenticate:
114  rospy.loginfo("Awaiting proper authentication...")
115 
116  @log_exceptions
117  def on_message(self, message):
118  cls = self.__class__
119  # check if we need to authenticate
120  if cls.authenticate and not self.authenticated:
121  try:
122  if cls.bson_only_mode:
123  msg = bson.BSON(message).decode()
124  else:
125  msg = json.loads(message)
126 
127  if msg['op'] == 'auth':
128  # check the authorization information
129  auth_srv = rospy.ServiceProxy('authenticate', Authentication)
130  resp = auth_srv(msg['mac'], msg['client'], msg['dest'],
131  msg['rand'], rospy.Time(msg['t']), msg['level'],
132  rospy.Time(msg['end']))
133  self.authenticated = resp.authenticated
134  if self.authenticated:
135  rospy.loginfo("Client %d has authenticated.", self.protocol.client_id)
136  return
137  # if we are here, no valid authentication was given
138  rospy.logwarn("Client %d did not authenticate. Closing connection.",
139  self.protocol.client_id)
140  self.close()
141  except:
142  # proper error will be handled in the protocol class
143  self.protocol.incoming(message)
144  else:
145  # no authentication required
146  self.protocol.incoming(message)
147 
148  @log_exceptions
149  def on_close(self):
150  cls = self.__class__
151  cls.clients_connected -= 1
152  self.protocol.finish()
153  if cls.client_manager:
154  cls.client_manager.remove_client(self.client_id, self.request.remote_ip)
155  rospy.loginfo("Client disconnected. %d clients total.", cls.clients_connected)
156 
157  def send_message(self, message):
158  if type(message) == bson.BSON:
159  binary = True
160  elif type(message) == bytearray:
161  binary = True
162  message = bytes(message)
163  else:
164  binary = False
165 
166  with self._write_lock:
167  IOLoop.instance().add_callback(partial(self.prewrite_message, message, binary))
168 
169  @coroutine
170  def prewrite_message(self, message, binary):
171  # Use a try block because the log decorator doesn't cooperate with @coroutine.
172  try:
173  with self._write_lock:
174  future = self.write_message(message, binary)
175 
176  # When closing, self.write_message() return None even if it's an undocument output.
177  # Consider it as WebSocketClosedError
178  # For tornado versions <4.3.0 self.write_message() does not have a return value
179  if future is None and tornado_version_info >= (4,3,0,0):
180  raise WebSocketClosedError
181 
182  yield future
183  except WebSocketClosedError:
184  rospy.logwarn_throttle(1, 'WebSocketClosedError: Tried to write to a closed websocket')
185  raise
186  except StreamClosedError:
187  rospy.logwarn_throttle(1, 'StreamClosedError: Tried to write to a closed stream')
188  raise
189  except BadYieldError:
190  # Tornado <4.5.0 doesn't like its own yield and raises BadYieldError.
191  # This does not affect functionality, so pass silently only in this case.
192  if tornado_version_info < (4, 5, 0, 0):
193  pass
194  else:
196  raise
197  except:
199  raise
200 
201  @log_exceptions
202  def check_origin(self, origin):
203  return True
204 
205  @log_exceptions
207  # If this method returns None (the default), compression will be disabled.
208  # If it returns a dict (even an empty one), it will be enabled.
209  cls = self.__class__
210 
211  if not cls.use_compression:
212  return None
213 
214  return {}


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