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
00034 import rospy
00035 import json
00036
00037 from rosauth.srv import Authentication
00038
00039 from signal import signal, SIGINT, SIG_DFL
00040 from functools import partial
00041
00042 from tornado.ioloop import IOLoop
00043 from tornado.web import Application
00044 from tornado.websocket import WebSocketHandler
00045
00046 from rosbridge_library.rosbridge_protocol import RosbridgeProtocol
00047
00048 import sys
00049
00050
00051 client_id_seed = 0
00052 clients_connected = 0
00053
00054 authenticate = False
00055
00056 class RosbridgeWebSocket(WebSocketHandler):
00057
00058 def open(self):
00059 global client_id_seed, clients_connected, authenticate
00060 try:
00061 self.protocol = RosbridgeProtocol(client_id_seed)
00062 self.protocol.outgoing = self.send_message
00063 self.authenticated = False
00064 client_id_seed = client_id_seed + 1
00065 clients_connected = clients_connected + 1
00066 except Exception as exc:
00067 rospy.logerr("Unable to accept incoming connection. Reason: %s", str(exc))
00068 rospy.loginfo("Client connected. %d clients total.", clients_connected)
00069 if authenticate:
00070 rospy.loginfo("Awaiting proper authentication...")
00071
00072 def on_message(self, message):
00073 global authenticate
00074
00075 if authenticate and not self.authenticated:
00076 try:
00077 msg = json.loads(message)
00078 if msg['op'] == 'auth':
00079
00080 auth_srv = rospy.ServiceProxy('authenticate', Authentication)
00081 resp = auth_srv(msg['mac'], msg['client'], msg['dest'],
00082 msg['rand'], rospy.Time(msg['t']), msg['level'],
00083 rospy.Time(msg['end']))
00084 self.authenticated = resp.authenticated
00085 if self.authenticated:
00086 rospy.loginfo("Client %d has authenticated.", self.protocol.client_id)
00087 return
00088
00089 rospy.logwarn("Client %d did not authenticate. Closing connection.",
00090 self.protocol.client_id)
00091 self.close()
00092 except:
00093
00094 self.protocol.incoming(message)
00095 else:
00096
00097 self.protocol.incoming(message)
00098
00099 def on_close(self):
00100 global clients_connected
00101 clients_connected = clients_connected - 1
00102 self.protocol.finish()
00103 rospy.loginfo("Client disconnected. %d clients total.", clients_connected)
00104
00105 def send_message(self, message):
00106 IOLoop.instance().add_callback(partial(self.write_message, message))
00107
00108 if __name__ == "__main__":
00109 rospy.init_node("rosbridge_websocket")
00110 signal(SIGINT, SIG_DFL)
00111
00112
00113 certfile = rospy.get_param('~certfile', None)
00114 keyfile = rospy.get_param('~keyfile', None)
00115
00116 authenticate = rospy.get_param('~authenticate', False)
00117 port = rospy.get_param('~port', 9090)
00118 address = rospy.get_param('~address', "")
00119
00120 if "--port" in sys.argv:
00121 idx = sys.argv.index("--port")+1
00122 if idx < len(sys.argv):
00123 port = int(sys.argv[idx])
00124 else:
00125 print "--port argument provided without a value."
00126 sys.exit(-1)
00127
00128 application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)])
00129 if certfile is not None and keyfile is not None:
00130 application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile})
00131 else:
00132 application.listen(port, address)
00133 rospy.loginfo("Rosbridge WebSocket server started on port %d", port)
00134
00135 IOLoop.instance().start()