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


rosbridge_server
Author(s): Jonathan Mace
autogenerated on Wed Sep 13 2017 03:18:20