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
00052
00053 fragment_timeout = 600
00054
00055 delay_between_messages = 0
00056 max_message_size = None
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
00083 if cls.authenticate and not self.authenticated:
00084 try:
00085 msg = json.loads(message)
00086 if msg['op'] == 'auth':
00087
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
00097 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00098 self.protocol.client_id)
00099 self.close()
00100 except:
00101
00102 self.protocol.incoming(message)
00103 else:
00104
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