Skip to content

Commit

Permalink
trying to deploy leaflets from client_node
Browse files Browse the repository at this point in the history
  • Loading branch information
a20r committed Sep 25, 2017
1 parent 96b8879 commit cf80107
Show file tree
Hide file tree
Showing 2 changed files with 51 additions and 10 deletions.
28 changes: 28 additions & 0 deletions launch/example_paas.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>
<launch>
<arg name="host" default="raphaelchang.com" />
<arg name="port" default="8080"/>
<node pkg="canopy_client" type="client_node.py" name="qux_client_node" output="screen">
<param name="name" value="qux"/>
<param name="host" value="$(arg host)"/>
<param name="port" value="$(arg port)"/>
<param name="private_key" value="PsFXjmWpszr6acSKL" />
<param name="description" value="qux robot" />
<rosparam>
publishing:
- /state
- /filtered_state
- /test_string
types:
- geometry_msgs/Point
- geometry_msgs/Point
- std_msgs/String
trusted:
- ".*"
- foo bar
- "ba[a-z]"
leaflets:
- https://github.com/canopy-ros/canopy_paas_demo
</rosparam>
</node>
</launch>
33 changes: 23 additions & 10 deletions src/client_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

import rospy
import time
import requests
import publishermanager as pm
from rospy_message_converter import message_converter as mc
from connection import Connection
Expand All @@ -11,13 +12,15 @@

NODE_NAME = "canopy_client"

# The ROS node object for the Canopy client.
# Manages all connections and subscribing.
# One instance per client node.
class CanopyClientNode(object):

class CanopyClientNode(object):
"""
The ROS node object for the Canopy client.
Manages all connections and subscribing.
One instance per client node.
"""
def __init__(self, host, port, name, broadcasting, private_key,
description, global_frames):
description, global_frames, leaflets):
self.host = host
self.port = port
self.name = name.replace(" ", "").replace("/", "")
Expand All @@ -29,9 +32,17 @@ def __init__(self, host, port, name, broadcasting, private_key,
self.private_key = private_key
self.description = description
self.global_frames = global_frames
self.leaflets = leaflets
self.pub_man = pm.PublisherManager()
self.timer = threading.Timer(0.1, self.descriptionSend)

def post_leaflet_urls(self):
payload = {"urls": self.leaflets}
post_url = "http://{}:{}/{}/leaflets".format(
self.host, self.port, self.private_key)
r = requests.post(post_url, data=payload)
return r

# Creates all connections and subscribers and starts them.
# Runs a loop that checks for received messages.
def run(self):
Expand All @@ -53,6 +64,7 @@ def run(self):
self.receiver.start()
self.descriptionConn.start()
self.timer.start()
self.post_leaflet_urls()
while not rospy.is_shutdown():
#for key, conn in self.conn.iteritems():
# updates = conn.updates()
Expand All @@ -61,7 +73,7 @@ def run(self):
self.pub_man.publish(v)
for key, conn in self.conn.iteritems():
conn.stop()
self.receiver.stop()
self.receiver.stop()
self.timer.cancel()
self.descriptionConn.stop()

Expand Down Expand Up @@ -108,7 +120,7 @@ def modify_stamped_message(self, message):
if message.child_frame_id[0] != "/":
message.child_frame_id = "/" + message.child_frame_id
message.child_frame_id = "{}{}".format(self.name,
message.child_frame_id)
message.child_frame_id)
if hasattr(message, 'header'):
if ((not hasattr(message, 'child_frame_id')) and
message.header.frame_id.find("/") > 0 and
Expand All @@ -120,8 +132,8 @@ def modify_stamped_message(self, message):
message.header.frame_id.count("/") <= 1):
if message.header.frame_id[0] != "/":
message.header.frame_id = "/" + message.header.frame_id
message.header.frame_id = "{}{}".format(self.name,
message.header.frame_id)
message.header.frame_id = "{}{}".format(
self.name, message.header.frame_id)
return message

# Periodic function to send the client description.
Expand All @@ -147,11 +159,12 @@ def descriptionSend(self):
types = rospy.get_param("~types", [])
trusted = rospy.get_param("~trusted", [])
global_frames = rospy.get_param("~global_frames", [])
leaflets = rospy.get_param("leaflets", [])
host = rospy.get_param("~host")
port = rospy.get_param("~port")
private_key = rospy.get_param("~private_key")
description = rospy.get_param("~description")
broadcasting = zip(topics, types, trusted)
rcn = CanopyClientNode(host, port, name, broadcasting, private_key,
description, global_frames)
description, global_frames, leaflets)
rcn.run()

0 comments on commit cf80107

Please sign in to comment.