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.websocket import WebSocketHandler, WebSocketClosedError
46 from tornado.gen import coroutine, BadYieldError
47 
48 from rosbridge_library.rosbridge_protocol import RosbridgeProtocol
49 from rosbridge_library.util import json, bson
50 
51 
53  """Log the most recent exception to ROS."""
54  exc = traceback.format_exception(*sys.exc_info())
55  rospy.logerr(''.join(exc))
56 
57 
59  """Decorator for logging exceptions to ROS."""
60  @wraps(f)
61  def wrapper(*args, **kwargs):
62  try:
63  return f(*args, **kwargs)
64  except:
66  raise
67  return wrapper
68 
69 
70 class RosbridgeWebSocket(WebSocketHandler):
71  client_id_seed = 0
72  clients_connected = 0
73  authenticate = False
74  use_compression = False
75 
76  # The following are passed on to RosbridgeProtocol
77  # defragmentation.py:
78  fragment_timeout = 600 # seconds
79  # protocol.py:
80  delay_between_messages = 0 # seconds
81  max_message_size = None # bytes
82  unregister_timeout = 10.0 # seconds
83  bson_only_mode = False
84 
85  @log_exceptions
86  def open(self):
87  cls = self.__class__
88  parameters = {
89  "fragment_timeout": cls.fragment_timeout,
90  "delay_between_messages": cls.delay_between_messages,
91  "max_message_size": cls.max_message_size,
92  "unregister_timeout": cls.unregister_timeout,
93  "bson_only_mode": cls.bson_only_mode
94  }
95  try:
96  self.protocol = RosbridgeProtocol(cls.client_id_seed, parameters=parameters)
97  self.protocol.outgoing = self.send_message
98  self.set_nodelay(True)
99  self.authenticated = False
100  self._write_lock = threading.RLock()
101  cls.client_id_seed += 1
102  cls.clients_connected += 1
103  self.client_id = uuid.uuid4()
104  if cls.client_manager:
105  cls.client_manager.add_client(self.client_id, self.request.remote_ip)
106  except Exception as exc:
107  rospy.logerr("Unable to accept incoming connection. Reason: %s", str(exc))
108  rospy.loginfo("Client connected. %d clients total.", cls.clients_connected)
109  if cls.authenticate:
110  rospy.loginfo("Awaiting proper authentication...")
111 
112  @log_exceptions
113  def on_message(self, message):
114  cls = self.__class__
115  # check if we need to authenticate
116  if cls.authenticate and not self.authenticated:
117  try:
118  if cls.bson_only_mode:
119  msg = bson.BSON(message).decode()
120  else:
121  msg = json.loads(message)
122 
123  if msg['op'] == 'auth':
124  # check the authorization information
125  auth_srv = rospy.ServiceProxy('authenticate', Authentication)
126  resp = auth_srv(msg['mac'], msg['client'], msg['dest'],
127  msg['rand'], rospy.Time(msg['t']), msg['level'],
128  rospy.Time(msg['end']))
129  self.authenticated = resp.authenticated
130  if self.authenticated:
131  rospy.loginfo("Client %d has authenticated.", self.protocol.client_id)
132  return
133  # if we are here, no valid authentication was given
134  rospy.logwarn("Client %d did not authenticate. Closing connection.",
135  self.protocol.client_id)
136  self.close()
137  except:
138  # proper error will be handled in the protocol class
139  self.protocol.incoming(message)
140  else:
141  # no authentication required
142  self.protocol.incoming(message)
143 
144  @log_exceptions
145  def on_close(self):
146  cls = self.__class__
147  cls.clients_connected -= 1
148  self.protocol.finish()
149  if cls.client_manager:
150  cls.client_manager.remove_client(self.client_id, self.request.remote_ip)
151  rospy.loginfo("Client disconnected. %d clients total.", cls.clients_connected)
152 
153  def send_message(self, message):
154  if type(message) == bson.BSON:
155  binary = True
156  elif type(message) == bytearray:
157  binary = True
158  message = bytes(message)
159  else:
160  binary = False
161 
162  with self._write_lock:
163  IOLoop.instance().add_callback(partial(self.prewrite_message, message, binary))
164 
165  @coroutine
166  def prewrite_message(self, message, binary):
167  # Use a try block because the log decorator doesn't cooperate with @coroutine.
168  try:
169  with self._write_lock:
170  yield self.write_message(message, binary)
171  except WebSocketClosedError:
172  rospy.logwarn('WebSocketClosedError: Tried to write to a closed websocket')
173  raise
174  except BadYieldError:
175  # Tornado <4.5.0 doesn't like its own yield and raises BadYieldError.
176  # This does not affect functionality, so pass silently only in this case.
177  if tornado_version_info < (4, 5, 0, 0):
178  pass
179  else:
181  raise
182  except:
184  raise
185 
186  @log_exceptions
187  def check_origin(self, origin):
188  return True
189 
190  @log_exceptions
192  # If this method returns None (the default), compression will be disabled.
193  # If it returns a dict (even an empty one), it will be enabled.
194  cls = self.__class__
195 
196  if not cls.use_compression:
197  return None
198 
199  return {}


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Fri May 10 2019 02:17:05