Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
00069 if cls.authenticate and not self.authenticated:
00070 try:
00071 msg = json.loads(message)
00072 if msg['op'] == 'auth':
00073
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
00083 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00084 self.protocol.client_id)
00085 self.close()
00086 except:
00087
00088 self.protocol.incoming(message)
00089 else:
00090
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