Skip to content

Commit

Permalink
Trying to make the bloody thing faster
Browse files Browse the repository at this point in the history
  • Loading branch information
a20r committed Feb 3, 2016
1 parent 2b01ca6 commit 41df41b
Show file tree
Hide file tree
Showing 6 changed files with 17 additions and 19 deletions.
14 changes: 7 additions & 7 deletions launch/example.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,11 @@
<?xml version="1.0"?>
<launch>
<node pkg="jammi" type="client_node.py" name="foo_node" output="screen">
<node pkg="jammi" type="server_node.py" name="jammi_server" output="screen">
<param name="host" value="localhost"/>
<param name="port" value="9000"/>
</node>

<node pkg="jammi" type="client_node.py" name="foo_client_node" output="screen">
<param name="name" value="foo"/>
<param name="host" value="localhost"/>
<param name="port" value="9000"/>
Expand All @@ -12,7 +17,7 @@
</rosparam>
</node>

<node pkg="jammi" type="client_node.py" name="bar_node" output="screen">
<node pkg="jammi" type="client_node.py" name="bar_client_node" output="screen">
<param name="name" value="bar"/>
<param name="host" value="localhost"/>
<param name="port" value="9000"/>
Expand All @@ -24,11 +29,6 @@
</rosparam>
</node>

<node pkg="jammi" type="server_node.py" name="jammi_server" output="screen">
<param name="host" value="localhost"/>
<param name="port" value="9000"/>
</node>

<node pkg="rostopic" type="rostopic" name="state_pub"
args="pub -r 100 /state geometry_msgs/Point '{x: 1, y: 1, z: 0}'"/>
</launch>
4 changes: 1 addition & 3 deletions src/client/client_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import rospy
import time
import publishermanager as pm
import json
from rospy_message_converter import message_converter as mc
from connection import Connection

Expand Down Expand Up @@ -48,8 +47,7 @@ def callback(msg):
data["type"] = msg_type
data["stamp"] = time.time()
data["msg"] = mc.convert_ros_message_to_dictionary(msg)
payload = json.dumps(data)
self.conn.send_message(payload)
self.conn.send_message(data)
return callback


Expand Down
8 changes: 4 additions & 4 deletions src/client/connection.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@

# import zlib
import threading
import string
import sys
import json
import copy
from twisted.internet import reactor
Expand All @@ -20,7 +19,7 @@ def onConnect(self, reponse):
def onMessage(self, payload, is_binary):
if not is_binary:
data = json.loads(payload)
MMClient.updates[data["topic"]] = payload
MMClient.updates[data["topic"]] = data

@staticmethod
def send_message(payload):
Expand All @@ -46,7 +45,8 @@ def run(self):
def stop(self):
reactor.stop()

def send_message(self, payload):
def send_message(self, data):
payload = json.dumps(data)
return MMClient.send_message(payload)

def updates(self):
Expand Down
5 changes: 2 additions & 3 deletions src/client/publishermanager.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@

import rospy
import json
from rospy_message_converter import message_converter


Expand All @@ -16,8 +16,7 @@ def create_msg(self, msg_dict, msg_type):
msg_type, msg_dict)
return msg, msg_cls

def publish(self, payload):
data = json.loads(payload)
def publish(self, data):
msg, msg_cls = self.create_msg(data["msg"], data["type"])
topic = data["topic"]
if not topic in self.pubs.keys():
Expand Down
4 changes: 2 additions & 2 deletions src/server/server_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,6 @@ def run_server(host, port):

if __name__ == "__main__":
rospy.init_node(NODE_NAME, anonymous=False)
host = rospy.get_param("~host")
port = rospy.get_param("~port")
host = rospy.get_param("~host", "localhost")
port = rospy.get_param("~port", 9000)
run_server(host, port)
1 change: 1 addition & 0 deletions src/server/ws.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@

# import zlib
import json
import common
from autobahn.twisted.websocket import WebSocketServerProtocol
Expand Down

0 comments on commit 41df41b

Please sign in to comment.