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
00044 import bson
00045 
00046 class RosbridgeWebSocket(WebSocketHandler):
00047     client_id_seed = 0
00048     clients_connected = 0
00049     authenticate = False
00050 
00051     def open(self):
00052         cls = self.__class__
00053         try:
00054             self.protocol = RosbridgeProtocol(cls.client_id_seed)
00055             self.protocol.outgoing = self.send_message
00056             self.set_nodelay(True)
00057             self.authenticated = False
00058             cls.client_id_seed += 1
00059             cls.clients_connected += 1
00060         except Exception as exc:
00061             rospy.logerr("Unable to accept incoming connection.  Reason: %s", str(exc))
00062         rospy.loginfo("Client connected.  %d clients total.", cls.clients_connected)
00063         if cls.authenticate:
00064             rospy.loginfo("Awaiting proper authentication...")
00065 
00066     def on_message(self, message):
00067         cls = self.__class__
00068         # check if we need to authenticate
00069         if cls.authenticate and not self.authenticated:
00070             try:
00071                 msg = json.loads(message)
00072                 if msg['op'] == 'auth':
00073                     # check the authorization information
00074                     auth_srv = rospy.ServiceProxy('authenticate', Authentication)
00075                     resp = auth_srv(msg['mac'], msg['client'], msg['dest'],
00076                                                   msg['rand'], rospy.Time(msg['t']), msg['level'],
00077                                                   rospy.Time(msg['end']))
00078                     self.authenticated = resp.authenticated
00079                     if self.authenticated:
00080                         rospy.loginfo("Client %d has authenticated.", self.protocol.client_id)
00081                         return
00082                 # if we are here, no valid authentication was given
00083                 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00084                               self.protocol.client_id)
00085                 self.close()
00086             except:
00087                 # proper error will be handled in the protocol class
00088                 self.protocol.incoming(message)
00089         else:
00090             # no authentication required
00091             self.protocol.incoming(message)
00092 
00093     def on_close(self):
00094         cls = self.__class__
00095         cls.clients_connected -= 1
00096         self.protocol.finish()
00097         rospy.loginfo("Client disconnected. %d clients total.", cls.clients_connected)
00098 
00099     def send_message(self, message):
00100         binary = type(message)==bson.BSON
00101         IOLoop.instance().add_callback(partial(self.write_message, message, binary))
00102 
00103     def check_origin(self, origin):
00104         return True


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Thu Aug 27 2015 14:50:40