Skip to content

Commit

Permalink
Merge pull request RobotWebTools#13 from Shokman/add_authen_author_tu…
Browse files Browse the repository at this point in the history
…rtlebot_demo

Add authen author turtlebot demo
  • Loading branch information
Julian Cerruti committed Mar 27, 2015
2 parents d71ea09 + e53d3d5 commit 1a6e732
Show file tree
Hide file tree
Showing 4 changed files with 93 additions and 29 deletions.
5 changes: 4 additions & 1 deletion rosbridge_server/launch/rosbridge_websocket.launch
Original file line number Diff line number Diff line change
@@ -1,23 +1,26 @@
<launch>
<arg name="port" default="9090" />
<arg name="address" default="" />
<arg name="address" default="localhost" />
<arg name="ssl" default="false" />
<arg name="certfile" />
<arg name="keyfile" />
<arg name="authenticate" default="false" />
<arg name="enable_authentication" default="false" />

<group if="$(arg ssl)">
<node name="rosbridge_websocket" pkg="rosbridge_server" type="rosbridge_websocket" output="screen">
<param name="certfile" value="$(arg certfile)" />
<param name="keyfile" value="$(arg keyfile)" />
<param name="authenticate" value="$(arg authenticate)" />
<param name="user_auth" value="$(arg enable_authentication)" />
<param name="port" value="$(arg port)"/>
<param name="address" value="$(arg address)"/>
</node>
</group>
<group unless="$(arg ssl)">
<node name="rosbridge_websocket" pkg="rosbridge_server" type="rosbridge_websocket" output="screen">
<param name="authenticate" value="$(arg authenticate)" />
<param name="user_auth" value="$(arg enable_authentication)" />
<param name="port" value="$(arg port)"/>
<param name="address" value="$(arg address)"/>
</node>
Expand Down
3 changes: 3 additions & 0 deletions rosbridge_server/launch/rosbridge_websocket_client.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,15 @@
<arg name="certfile" />
<arg name="keyfile" />
<arg name="authenticate" default="false" />
<arg name="enable_authentication" default="false" />
<arg name="webserver_uri" default="ws://localhost:9090" />

<group if="$(arg ssl)">
<node name="rosbridge_websocket_client" pkg="rosbridge_server" type="rosbridge_websocket_client" output="screen">
<param name="certfile" value="$(arg certfile)" />
<param name="keyfile" value="$(arg keyfile)" />
<param name="authenticate" value="$(arg authenticate)" />
<param name="user_auth" value="$(arg enable_authentication)" />
<param name="port" value="$(arg port)"/>
<param name="address" value="$(arg address)"/>
<param name="webserver_uri" value="$(arg webserver_uri)"/>
Expand All @@ -18,6 +20,7 @@
<group unless="$(arg ssl)">
<node name="rosbridge_websocket_client" pkg="rosbridge_server" type="rosbridge_websocket_client" output="screen">
<param name="authenticate" value="$(arg authenticate)" />
<param name="user_auth" value="$(arg enable_authentication)" />
<param name="webserver_uri" value="$(arg webserver_uri)"/>
</node>
</group>
Expand Down
63 changes: 48 additions & 15 deletions rosbridge_server/scripts/rosbridge_websocket.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -52,41 +53,70 @@
# 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
self.authenticated = False
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
Expand All @@ -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))
Expand All @@ -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', "")

Expand All @@ -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)
Expand Down
51 changes: 38 additions & 13 deletions rosbridge_server/scripts/rosbridge_websocket_client.py
Original file line number Diff line number Diff line change
@@ -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

Expand All @@ -18,7 +20,7 @@

ws = None
protocol = None

user_auth = False
webserver_port = 8080

# WebsocketClientTornado
Expand All @@ -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)
Expand Down Expand Up @@ -65,21 +69,43 @@ 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"}')
elif msg['op'] == "endVideo":
#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):
Expand All @@ -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()

Expand Down Expand Up @@ -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)
Expand Down

0 comments on commit 1a6e732

Please sign in to comment.