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, bson
00044
00045 class RosbridgeWebSocket(WebSocketHandler):
00046 client_id_seed = 0
00047 clients_connected = 0
00048 authenticate = False
00049
00050
00051
00052 fragment_timeout = 600
00053
00054 delay_between_messages = 0
00055 max_message_size = None
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
00082 if cls.authenticate and not self.authenticated:
00083 try:
00084 msg = json.loads(message)
00085 if msg['op'] == 'auth':
00086
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
00096 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00097 self.protocol.client_id)
00098 self.close()
00099 except:
00100
00101 self.protocol.incoming(message)
00102 else:
00103
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