websocket_handler.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 
00033 import rospy
00034 
00035 from rosauth.srv import Authentication
00036 
00037 from functools import partial
00038 
00039 from tornado.ioloop import IOLoop
00040 from tornado.websocket import WebSocketHandler
00041 
00042 from rosbridge_library.rosbridge_protocol import RosbridgeProtocol
00043 from rosbridge_library.util import json, bson
00044 
00045 class RosbridgeWebSocket(WebSocketHandler):
00046     client_id_seed = 0
00047     clients_connected = 0
00048     authenticate = False
00049 
00050     # The following are passed on to RosbridgeProtocol
00051     # defragmentation.py:
00052     fragment_timeout = 600                  # seconds
00053     # protocol.py:
00054     delay_between_messages = 0              # seconds
00055     max_message_size = None                 # bytes
00056     bson_only_mode = False
00057 
00058     def open(self):
00059         cls = self.__class__
00060         parameters = {
00061             "fragment_timeout": cls.fragment_timeout,
00062             "delay_between_messages": cls.delay_between_messages,
00063             "max_message_size": cls.max_message_size,
00064             "bson_only_mode": cls.bson_only_mode
00065         }
00066         try:
00067             self.protocol = RosbridgeProtocol(cls.client_id_seed, parameters=parameters)
00068             self.protocol.outgoing = self.send_message
00069             self.set_nodelay(True)
00070             self.authenticated = False
00071             cls.client_id_seed += 1
00072             cls.clients_connected += 1
00073         except Exception as exc:
00074             rospy.logerr("Unable to accept incoming connection.  Reason: %s", str(exc))
00075         rospy.loginfo("Client connected.  %d clients total.", cls.clients_connected)
00076         if cls.authenticate:
00077             rospy.loginfo("Awaiting proper authentication...")
00078 
00079     def on_message(self, message):
00080         cls = self.__class__
00081         # check if we need to authenticate
00082         if cls.authenticate and not self.authenticated:
00083             try:
00084                 msg = json.loads(message)
00085                 if msg['op'] == 'auth':
00086                     # check the authorization information
00087                     auth_srv = rospy.ServiceProxy('authenticate', Authentication)
00088                     resp = auth_srv(msg['mac'], msg['client'], msg['dest'],
00089                                                   msg['rand'], rospy.Time(msg['t']), msg['level'],
00090                                                   rospy.Time(msg['end']))
00091                     self.authenticated = resp.authenticated
00092                     if self.authenticated:
00093                         rospy.loginfo("Client %d has authenticated.", self.protocol.client_id)
00094                         return
00095                 # if we are here, no valid authentication was given
00096                 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00097                               self.protocol.client_id)
00098                 self.close()
00099             except:
00100                 # proper error will be handled in the protocol class
00101                 self.protocol.incoming(message)
00102         else:
00103             # no authentication required
00104             self.protocol.incoming(message)
00105 
00106     def on_close(self):
00107         cls = self.__class__
00108         cls.clients_connected -= 1
00109         self.protocol.finish()
00110         rospy.loginfo("Client disconnected. %d clients total.", cls.clients_connected)
00111 
00112     def send_message(self, message):
00113         binary = type(message)==bson.BSON
00114         IOLoop.instance().add_callback(partial(self.write_message, message, binary))
00115 
00116     def check_origin(self, origin):
00117         return True


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Thu Jun 6 2019 21:51:51