diff --git a/rosbridge_server/launch/rosbridge_websocket.launch b/rosbridge_server/launch/rosbridge_websocket.launch index f0de5d4e8..533f72d06 100644 --- a/rosbridge_server/launch/rosbridge_websocket.launch +++ b/rosbridge_server/launch/rosbridge_websocket.launch @@ -1,16 +1,18 @@ - + + + @@ -18,6 +20,7 @@ + diff --git a/rosbridge_server/launch/rosbridge_websocket_client.launch b/rosbridge_server/launch/rosbridge_websocket_client.launch index 7a3604496..371a85ac5 100644 --- a/rosbridge_server/launch/rosbridge_websocket_client.launch +++ b/rosbridge_server/launch/rosbridge_websocket_client.launch @@ -3,6 +3,7 @@ + @@ -10,6 +11,7 @@ + @@ -18,6 +20,7 @@ + diff --git a/rosbridge_server/scripts/rosbridge_websocket.py b/rosbridge_server/scripts/rosbridge_websocket.py index e50e60136..1f84568d5 100755 --- a/rosbridge_server/scripts/rosbridge_websocket.py +++ b/rosbridge_server/scripts/rosbridge_websocket.py @@ -35,6 +35,7 @@ import sys from rosauth.srv import Authentication +from rosauth.srv import UserAuthentication from signal import signal, SIGINT, SIG_DFL from functools import partial @@ -52,10 +53,11 @@ # if authentication should be used authenticate = False + class RosbridgeWebSocket(WebSocketHandler): def open(self): - global client_id_seed, clients_connected, authenticate + global client_id_seed, clients_connected, authenticate, user_auth try: self.protocol = RosbridgeProtocol(client_id_seed) self.protocol.outgoing = self.send_message @@ -63,30 +65,58 @@ def open(self): client_id_seed = client_id_seed + 1 clients_connected = clients_connected + 1 except Exception as exc: - rospy.logerr("Unable to accept incoming connection. Reason: %s", str(exc)) - rospy.loginfo("Client connected. %d clients total.", clients_connected) - if authenticate: + rospy.logerr("Unable to accept incoming connection. Reason: %s", + str(exc)) + rospy.loginfo("Client connected. %d clients total.", + clients_connected) + if authenticate or user_auth: rospy.loginfo("Awaiting proper authentication...") def on_message(self, message): - global authenticate + global authenticate, user_auth # check if we need to authenticate + if authenticate and not self.authenticated: try: msg = json.loads(message) if msg['op'] == 'auth': # check the authorization information - auth_srv = rospy.ServiceProxy('authenticate', Authentication) - resp = auth_srv(msg['mac'], msg['client'], msg['dest'], - msg['rand'], rospy.Time(msg['t']), msg['level'], - rospy.Time(msg['end'])) + auth_srv = rospy.ServiceProxy('authenticate', + Authentication) + resp = auth_srv(msg['mac'], msg['client'], msg['dest'], + msg['rand'], rospy.Time(msg['t']), + msg['level'], rospy.Time(msg['end'])) self.authenticated = resp.authenticated if self.authenticated: - rospy.loginfo("Client %d has authenticated.", self.protocol.client_id) + rospy.loginfo("Client %d has authenticated.", + self.protocol.client_id) return # if we are here, no valid authentication was given - rospy.logwarn("Client %d did not authenticate. Closing connection.", - self.protocol.client_id) + rospy.logwarn("Client %d did not authenticate. " + "Closing connection.", self.protocol.client_id) + self.close() + except: + rospy.logwarn("Error in authentication") + # proper error will be handled in the protocol class + self.protocol.incoming(message) + elif user_auth and not self.authenticated: + try: + msg = json.loads(message) + if msg['op'] == 'auth': + # check the authorization information + + auth_srv = rospy.ServiceProxy('/authenticate_user', + UserAuthentication) + resp = auth_srv(msg['user'], msg['pass']) + self.authenticated = resp.authenticated + + if self.authenticated: + rospy.loginfo("Client %d has authenticated.", + self.protocol.client_id) + return + # if we are here, no valid authentication was given + rospy.logwarn("Client %d did not authenticate. " + "Closing connection.", self.protocol.client_id) self.close() except: # proper error will be handled in the protocol class @@ -99,7 +129,8 @@ def on_close(self): global clients_connected clients_connected = clients_connected - 1 self.protocol.finish() - rospy.loginfo("Client disconnected. %d clients total.", clients_connected) + rospy.loginfo("Client disconnected. %d clients total.", + clients_connected) def send_message(self, message): IOLoop.instance().add_callback(partial(self.write_message, message)) @@ -116,6 +147,7 @@ def check_origin(self, origin): keyfile = rospy.get_param('~keyfile', None) # if authentication should be used authenticate = rospy.get_param('~authenticate', False) + user_auth = rospy.get_param('~user_auth', False) port = rospy.get_param('~port', 9090) address = rospy.get_param('~address', "") @@ -127,9 +159,10 @@ def check_origin(self, origin): print "--port argument provided without a value." sys.exit(-1) - application = Application([(r"/", RosbridgeWebSocket), (r"", RosbridgeWebSocket)]) + application = Application([(r"/ws", RosbridgeWebSocket), ]) if certfile is not None and keyfile is not None: - application.listen(port, address, ssl_options={ "certfile": certfile, "keyfile": keyfile}) + application.listen(port, address, ssl_options={"certfile": certfile, + "keyfile": keyfile}) else: application.listen(port, address) rospy.loginfo("Rosbridge WebSocket server started on port %d", port) diff --git a/rosbridge_server/scripts/rosbridge_websocket_client.py b/rosbridge_server/scripts/rosbridge_websocket_client.py index d42283fda..e110fdef1 100755 --- a/rosbridge_server/scripts/rosbridge_websocket_client.py +++ b/rosbridge_server/scripts/rosbridge_websocket_client.py @@ -1,11 +1,13 @@ #!/usr/bin/env python import rospy import signal -import tornado.httpclient import base64 import urllib import time +from rosauth.srv import UserAuthentication + +from tornado.httpclient import HTTPRequest, AsyncHTTPClient from tornado.websocket import websocket_connect from tornado.ioloop import IOLoop @@ -18,7 +20,7 @@ ws = None protocol = None - +user_auth = False webserver_port = 8080 # WebsocketClientTornado @@ -34,10 +36,12 @@ class WebsocketClientTornado(): keepalive = None def __init__(self, uri): + self.authenticated = False self.uri = uri self.doconn() def doconn(self): + global user_auth try: rospy.loginfo("trying connection to %s" % (self.uri,)) w = websocket_connect(self.uri) @@ -65,13 +69,15 @@ def wsconnection_cb(self, conn): timedelta(seconds=PING_TIMEOUT), self.dokeepalive) def message(self, _message): + global user_auth #print "Msg received: [%s]" % _message msg = json.loads(_message) if msg['op'] == 'video': try: args = msg['args'] - self.transfer = VideoTransfer("http://localhost:8080/stream", args, self) - except e: + self.transfer = VideoTransfer("http://localhost:8080/stream", + args, self) + except Exception as e: rospy.logerror("Could not connect to WebCam") rospy.logerror(e) self.send_message('{"op":"endVideo"}') @@ -79,7 +85,27 @@ def message(self, _message): #TODO Resolve stop from client self.transfer.endVideo() pass + elif msg['op'] == 'auth': + try: + # check the authorization information + if user_auth and not self.authenticated: + auth_srv = rospy.ServiceProxy('/authenticate_user', + UserAuthentication) + resp = auth_srv(msg['user'], msg['pass']) + self.authenticated = resp.authenticated + if self.authenticated: + rospy.loginfo("Client has authenticated") + return + # if we are here, no valid authentication was given + rospy.logwarn("Client did not authenticate. Closing " + "connection.") + # TODO: INSTRUCT TO THE SERVER TO DISCONNECT + except Exception as e: + rospy.logerr("Exception during authentication %s", e) + # proper error will be handled in the protocol class + self.protocol.incoming(_message) else: + # no authentication required protocol.incoming(_message) def close(self): @@ -94,19 +120,17 @@ def send_message(self, _message): self.conn.write_message(_message) #print "Msg sent: [%s]" % _message + class VideoTransfer(): def __init__(self, url, args, connection): - tornado.httpclient.AsyncHTTPClient.configure( - "tornado.curl_httpclient.CurlAsyncHTTPClient") + AsyncHTTPClient.configure("tornado.curl_httpclient." + "CurlAsyncHTTPClient") self.conn = connection url = url + "?" + urllib.urlencode(args) - url = url.replace("%2F","/") - req = tornado.httpclient.HTTPRequest( - url = url, - streaming_callback = self.streaming_callback, - connect_timeout = 0.0, - request_timeout = 0.0) - http_client = tornado.httpclient.AsyncHTTPClient() + url = url.replace("%2F", "/") + req = HTTPRequest(url=url, streaming_callback=self.streaming_callback, + connect_timeout=0.0, request_timeout=0.0) + http_client = AsyncHTTPClient() http_client.fetch(req, self.async_callback) self.start = time.time() @@ -136,6 +160,7 @@ def end_video(self): # Connect with server server_uri = rospy.get_param("~webserver_uri") + user_auth = rospy.get_param('~user_auth', False) # In the future we are going need to use everithing on the same port # given throught the argument ws = WebsocketClientTornado(server_uri)