From 4b048aeaea720b5f41cb9dcc86bd01ac5a6322ca Mon Sep 17 00:00:00 2001 From: Raphael Chang Date: Sat, 13 Feb 2016 16:14:52 -0500 Subject: [PATCH] Image sending tests --- launch/example.launch | 24 ++++++++++++++++++++---- launch/server.launch | 2 +- requirements.txt | 3 +-- src/client/connection.py | 5 +++++ 4 files changed, 27 insertions(+), 7 deletions(-) diff --git a/launch/example.launch b/launch/example.launch index b7e764e..9fcce05 100644 --- a/launch/example.launch +++ b/launch/example.launch @@ -3,35 +3,38 @@ - + - + - + - + publishing: - /state - /filtered_state + - /usb_cam/image_raw/compressed types: - geometry_msgs/Point - geometry_msgs/Point + - sensor_msgs/CompressedImage trusted: - "*" - foo bar + - foo @@ -40,4 +43,17 @@ args="pub -r 100 /state geometry_msgs/Point '{x: 1, y: 1, z: 0}'"/> + + + + + + + + + + + + + diff --git a/launch/server.launch b/launch/server.launch index 5c81f73..40808dc 100644 --- a/launch/server.launch +++ b/launch/server.launch @@ -2,7 +2,7 @@ - + diff --git a/requirements.txt b/requirements.txt index a70c577..c3368df 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,2 +1 @@ -twisted -autobahn +tornado diff --git a/src/client/connection.py b/src/client/connection.py index cc24f7a..5ee68ca 100644 --- a/src/client/connection.py +++ b/src/client/connection.py @@ -5,10 +5,12 @@ import copy import struct import rospy +import time import tornado.web import tornado.websocket import tornado.httpserver import tornado.ioloop +from std_msgs.msg import Float32 class Connection(threading.Thread): def __init__(self, host, port, name): @@ -22,6 +24,7 @@ def __init__(self, host, port, name): self.values = dict() self.acknowledged = True self.timer = threading.Timer + self.freqPub = rospy.Publisher("/{}/ping".format(name), Float32, queue_size=0) def run(self): tornado.websocket.websocket_connect( @@ -45,6 +48,8 @@ def send_message_cb(self, data): # rospy.loginfo(self.acknowledged) if self.acknowledged: self.acknowledged = False + if binLen > 1000: + self.freqPub.publish(0.0) self.connection.write_message(compressed, True) self.timer = threading.Timer(1, self.timeout) self.timer.start()