Skip to content

Commit

Permalink
Merge pull request #794 from garaemon/event-driven-mode
Browse files Browse the repository at this point in the history
[jsk_network_tools] Event driven mode to lowspeed streamer
  • Loading branch information
garaemon committed Feb 20, 2015
2 parents 6a21431 + e3f4b03 commit a315bb7
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 5 deletions.
2 changes: 2 additions & 0 deletions jsk_network_tools/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,9 @@ Features of `silverhammer_lowspeed_{streamer,receiver}.py` are:
* `~send_rate` (default: `1`)

Fixed rate in Hz to send message.
* `~event_driven` (default: `False`)

Streamer sends UDP packet immediately `~input` topic is published.
#### `silverhammer_lowspeed_receiver.py`
##### Publishing Topics
* `~output`
Expand Down
16 changes: 11 additions & 5 deletions jsk_network_tools/scripts/silverhammer_lowspeed_streamer.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,15 @@ def __init__(self):
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)
self.event_driven = rospy.get_param("~event_driven", False)
self.latest_message = None
self.socket_client = socket(AF_INET, SOCK_DGRAM)
self.send_format = msgToStructFormat(self.send_message())
self.sub = rospy.Subscriber("~input",
self.send_message, self.messageCallback)
self.send_timer = rospy.Timer(rospy.Duration(1 / self.send_rate),
self.sendTimerCallback)
if not self.event_driven:
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):
Expand All @@ -56,14 +58,18 @@ def messageCallback(self, msg):
with self.lock:
self.latest_message = msg
self.last_input_received_time = rospy.Time.now()
if self.event_driven:
self.sendMessage(msg)
def sendMessage(self, msg):
packed_data = packMessage(msg, self.send_format)
self.socket_client.sendto(packed_data, (self.to_ip, self.to_port))
self.last_send_time = rospy.Time.now()
def sendTimerCallback(self, event):
with self.lock:
if self.latest_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.sendMessage(self.latest_message)
self.latest_message = None
self.last_send_time = rospy.Time.now()
else:
rospy.loginfo("no message is available")

Expand Down

0 comments on commit a315bb7

Please sign in to comment.