From 54956775aaaf5396cdca459c2bf21c5f60dc35a9 Mon Sep 17 00:00:00 2001 From: Raphael Chang Date: Mon, 15 Feb 2016 20:03:55 -0500 Subject: [PATCH] Private keys --- CMakeLists.txt | 2 +- launch/example.launch | 20 ++++++++------------ launch/video_chat_demo.launch | 6 +++--- package.xml | 2 +- src/client_node.py | 11 +++++++---- src/connection.py | 12 ++++++++---- 6 files changed, 28 insertions(+), 25 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2a7c4f8..8c1783b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(roscloud) +project(roscloud_client) find_package(catkin REQUIRED COMPONENTS rospy diff --git a/launch/example.launch b/launch/example.launch index d0f1890..e096f2f 100644 --- a/launch/example.launch +++ b/launch/example.launch @@ -1,35 +1,31 @@ - + - - + - + - - + - + - - + - + - - + publishing: - /state diff --git a/launch/video_chat_demo.launch b/launch/video_chat_demo.launch index f8d3d07..200b0a5 100644 --- a/launch/video_chat_demo.launch +++ b/launch/video_chat_demo.launch @@ -1,7 +1,7 @@ - - + + @@ -10,7 +10,7 @@ types: - sensor_msgs/CompressedImage trusted: - - raphael + - alex diff --git a/package.xml b/package.xml index 844428b..0edf80b 100644 --- a/package.xml +++ b/package.xml @@ -1,6 +1,6 @@ - roscloud + roscloud_client 0.0.1 ROS Cloud Robotics Framework Alex Wallar diff --git a/src/client_node.py b/src/client_node.py index 10a600f..0f0da27 100755 --- a/src/client_node.py +++ b/src/client_node.py @@ -12,7 +12,7 @@ class ROSCloudNode(object): - def __init__(self, host, port, name, broadcasting): + def __init__(self, host, port, name, broadcasting, private_key): self.host = host self.port = port self.name = name @@ -20,6 +20,7 @@ def __init__(self, host, port, name, broadcasting): self.receiver = None self.subs = dict() self.broadcasting = broadcasting + self.private_key = private_key self.pub_man = pm.PublisherManager() def run(self): @@ -30,10 +31,10 @@ def run(self): self.name)) continue self.conn[topic] = Connection(host, port, "{}{}".format( - self.name, topic)) + self.name, topic), private_key) self.conn[topic].start() self.receiver = Connection(host, port, "{}{}".format( - self.name, "/receiving")) + self.name, "/receiving"), private_key) self.receiver.start() while not rospy.is_shutdown(): #for key, conn in self.conn.iteritems(): @@ -61,6 +62,7 @@ def callback(msg): data["Topic"] = "/{}{}".format(self.name, topic) data["Type"] = msg_type data["Stamp"] = time.time() + data["Private_key"] = self.private_key data["Msg"] = mc.convert_ros_message_to_dictionary(msg) self.conn[topic].send_message(data) return callback @@ -74,6 +76,7 @@ def callback(msg): trusted = rospy.get_param("~trusted", []) host = rospy.get_param("~host") port = rospy.get_param("~port") + private_key = rospy.get_param("~private_key") broadcasting = zip(topics, types, trusted) - rcn = ROSCloudNode(host, port, name, broadcasting) + rcn = ROSCloudNode(host, port, name, broadcasting, private_key) rcn.run() diff --git a/src/connection.py b/src/connection.py index 4a5ab59..963cc8d 100644 --- a/src/connection.py +++ b/src/connection.py @@ -14,12 +14,12 @@ class Connection(threading.Thread): - def __init__(self, host, port, name): + def __init__(self, host, port, name, private_key): super(Connection, self).__init__() self.host = host self.port = port self.name = name - self.url = "ws://{}:{}/{}".format(host, port, name) + self.url = "ws://{}:{}/{}/{}".format(host, port, private_key, name) self.ioloop = None self.connection = None self.values = dict() @@ -60,7 +60,8 @@ def send_message_cb(self, data): self.timer.start() def send_message(self, data): - self.ioloop.add_callback(self.send_message_cb, data) + if not self.ioloop is None: + self.ioloop.add_callback(self.send_message_cb, data) def updates(self): payloads = copy.copy(self.values) @@ -88,7 +89,10 @@ def on_connected(self, res): def on_message(self, payload): if len(payload) == 1: self.acknowledged = True - self.timer.cancel() + try: + self.timer.cancel() + except: + pass else: decompressed = zlib.decompress(payload) size = struct.unpack('=I', decompressed[:4])