Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[jsk_network_tools] Publish the last time to send/receive messages #774

Merged
merged 1 commit into from
Feb 14, 2015
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 23 additions & 2 deletions jsk_network_tools/scripts/silverhammer_highspeed_streamer.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

import roslib
from roslib.message import get_message_class
from std_msgs.msg import Time

class SilverHammerStreamer:
def __init__(self):
Expand All @@ -22,6 +23,11 @@ def __init__(self):
self.lock = Lock()
self.send_port = rospy.get_param("~to_port", 16484)
self.send_ip = rospy.get_param("~to_ip", "localhost")
self.last_send_time = None
self.last_input_received_time = None
self.last_send_time_pub = rospy.Publisher("~last_send_time", Time)
self.last_input_received_time_pub = rospy.Publisher(
"~last_input_received_time", Time)
self.rate = rospy.get_param("~send_rate", 2) #2Hz
self.socket_client = socket(AF_INET, SOCK_DGRAM)
self.packet_size = rospy.get_param("~packet_size", 1000) #2Hz
Expand All @@ -31,7 +37,20 @@ def __init__(self):
self.counter = 0
self.send_timer = rospy.Timer(rospy.Duration(1.0 / self.rate),
self.sendTimerCallback)

self.update_time_pub_timer = rospy.Timer(rospy.Duration(1.0 / 10),
self.timeTimerCallback)
def timeTimerCallback(self, event):
with self.lock:
if self.last_send_time:
self.last_send_time_pub.publish(self.last_send_time)
else:
self.last_send_time_pub.publish(Time(data=rospy.Time(0)))
if self.last_input_received_time:
self.last_input_received_time_pub.publish(
self.last_input_received_time)
else:
self.last_input_received_time_pub.publish(
Time(data=rospy.Time(0)))
def sendTimerCallback(self, event):
buffer = StringIO()
with self.lock:
Expand All @@ -42,11 +61,12 @@ def sendTimerCallback(self, event):
if topic in self.messages:
setattr(msg, field_name, self.messages[topic])
rospy.msg.serialize_message(buffer, 0, msg)
self.last_send_time = rospy.Time.now()
# send buffer as UDP
self.sendBuffer(buffer.getvalue())
def sendBuffer(self, buffer):
packets = separateBufferIntoPackets(self.counter, buffer, self.packet_size)
rospy.loginfo("sending %d packets", len(packets))
rospy.logdebug("sending %d packets", len(packets))
for p in packets:
self.socket_client.sendto(p.pack(), (self.send_ip, self.send_port))
self.counter = self.counter + 1
Expand All @@ -60,6 +80,7 @@ def subscribe(self, subscriber_infos):
def messageCallback(self, msg, topic):
with self.lock:
self.messages[topic] = msg
self.last_input_received_time = rospy.Time.now()
def genMessageCallback(self, topic):
return lambda msg: self.messageCallback(msg, topic)

Expand Down
38 changes: 27 additions & 11 deletions jsk_network_tools/scripts/silverhammer_lowspeed_receiver.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import sys
import roslib
from roslib.message import get_message_class
from std_msgs.msg import Time

class SilverHammerUDPListener():
def __init__(self, server, buffer_size, format, message, pub):
Expand All @@ -33,32 +34,47 @@ def __init__(self):
self.receive_message = get_message_class(message_class_str)
except:
raise Exception("invalid topic type: %s"%message_class_str)
self.lock = Lock()
self.receive_port = rospy.get_param("~receive_port", 1024)
self.receive_ip = rospy.get_param("~receive_ip", "127.0.0.1")
self.receive_buffer = rospy.get_param("~receive_buffer_size", 250)
self.socket_server = socket(AF_INET, SOCK_DGRAM)
self.socket_server.bind((self.receive_ip, self.receive_port))
self.receive_format = msgToStructFormat(self.receive_message())
self.pub = rospy.Publisher("~output", self.receive_message)
def messageCallback(self, msg):
self.last_received_time = None
self.last_received_time_pub = rospy.Publisher(
"~last_received_time", Time)
self.last_publish_output_time = None
self.last_publish_output_time_pub = rospy.Publisher(
"~last_publish_output_time", Time)
self.update_time_pub_timer = rospy.Timer(rospy.Duration(1.0 / 10),
self.timeTimerCallback)
def timeTimerCallback(self, event):
with self.lock:
self.latest_message = msg
def sendTimerCallback(self, event):
with self.lock:
if self.latest_message:
rospy.loginfo("sending message")
packed_data = packMessage(self.latest_message, self.send_format)
self.socket_client.sendto(packed_data, (self.to_ip, self.to_port))
self.latest_message = None
if self.last_received_time:
self.last_received_time_pub.publish(
Time(data=self.last_received_time))
else:
self.last_received_time_pub.publish(
Time(data=rospy.Time(0)))
if self.last_publish_output_time:
self.last_publish_output_time_pub.publish(
Time(data=self.last_publish_output_time))
else:
rospy.loginfo("no message is available")
self.last_publish_output_time_pub.publish(
Time(data=rospy.Time(0)))
def run(self):
while not rospy.is_shutdown():
recv_data, addr = self.socket_server.recvfrom(self.receive_buffer)
msg = unpackMessage(recv_data, self.receive_format,
self.receive_message)
with self.lock:
self.last_received_time = rospy.Time.now()
self.pub.publish(msg)
print "received:", msg
with self.lock:
self.last_publish_output_time = rospy.Time.now()
rospy.logdebug("received:", msg)

if __name__ == "__main__":
rospy.init_node("silverhammer_lowspeed_receiver")
Expand Down
26 changes: 23 additions & 3 deletions jsk_network_tools/scripts/silverhammer_lowspeed_streamer.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

import roslib
from roslib.message import get_message_class

from std_msgs.msg import Time

class SilverHammerLowspeedStreamer():
def __init__(self):
Expand All @@ -23,6 +23,11 @@ def __init__(self):
except:
raise Exception("invalid topic type: %s"%message_class_str)
self.lock = Lock()
self.last_send_time = None
self.last_input_received_time = None
self.last_send_time_pub = rospy.Publisher("~last_send_time", Time)
self.last_input_received_time_pub = rospy.Publisher(
"~last_input_received_time", Time)
self.to_port = rospy.get_param("~to_port", 1024)
self.to_ip = rospy.get_param("~to_ip", "127.0.0.1")
self.send_rate = rospy.get_param("~send_rate", 1)
Expand All @@ -33,19 +38,34 @@ def __init__(self):
self.send_message, self.messageCallback)
self.send_timer = rospy.Timer(rospy.Duration(1 / self.send_rate),
self.sendTimerCallback)
self.update_time_pub_timer = rospy.Timer(rospy.Duration(1.0 / 10),
self.timeTimerCallback)
def timeTimerCallback(self, event):
with self.lock:
if self.last_send_time:
self.last_send_time_pub.publish(self.last_send_time)
else:
self.last_send_time_pub.publish(Time(data=rospy.Time(0)))
if self.last_input_received_time:
self.last_input_received_time_pub.publish(
self.last_input_received_time)
else:
self.last_input_received_time_pub.publish(
Time(data=rospy.Time(0)))
def messageCallback(self, msg):
with self.lock:
self.latest_message = msg
self.last_input_received_time = rospy.Time.now()
def sendTimerCallback(self, event):
with self.lock:
if self.latest_message:
rospy.loginfo("sending message")
rospy.logdebug("sending message")
packed_data = packMessage(self.latest_message, self.send_format)
self.socket_client.sendto(packed_data, (self.to_ip, self.to_port))
self.latest_message = None
self.last_send_time = rospy.Time.now()
else:
rospy.loginfo("no message is available")


if __name__ == "__main__":
rospy.init_node("silverhammer_lowspeed_streamer")
Expand Down