network_status.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import re
00003 import rospy
00004 from std_msgs.msg import Float32
00005 from collections import deque
00006 
00007 class NetworkStatus():
00008     def __init__(self):
00009         rospy.init_node('network')
00010         self.match_face = re.compile('(.+):(.*)')
00011         self.hz = rospy.get_param('~hz', 100)
00012         rospy.logwarn('publish network status (bps) at ' +  str(self.hz) + 'Hz')
00013         rospy.logwarn('usage:\n$rosrun jsk_network_tools network_status.py _hz:=[Hz]')
00014         self.init_publisher()
00015         rospy.Timer(rospy.Duration(1.0/self.hz), self.publish)
00016         rospy.spin()
00017 
00018     def init_publisher(self):
00019         faces = self.read_net_file()
00020         self.faces_map = {}
00021         for face in faces:
00022             pub_transmit = rospy.Publisher(face[0] + '/transmit', Float32)
00023             pub_receive = rospy.Publisher(face[0] + '/receive', Float32)
00024             queue_transmit = deque()
00025             queue_reveice = deque()
00026 
00027             for i in range(self.hz):
00028                 queue_transmit.append(-1)
00029                 queue_reveice.append(-1)
00030 
00031             self.faces_map[face[0]] = {}
00032             self.faces_map[face[0]]["transmit"] = {"publisher": pub_transmit, "value": queue_transmit}
00033             self.faces_map[face[0]]["receive"] = {"publisher": pub_receive, "value": queue_reveice}
00034 
00035     def publish(self, event):
00036         faces = self.read_net_file()
00037         for face in faces:
00038             name = face[0]
00039 
00040             if name in self.faces_map:
00041                 self.faces_map[name]["transmit"]["value"].append(int(face[1]))
00042                 self.faces_map[name]["receive"]["value"].append(int(face[2]))
00043 
00044                 msg_transmit = Float32((int(face[1]) - self.faces_map[name]["transmit"]["value"].popleft()) * 8)
00045                 msg_receive = Float32((int(face[2]) - self.faces_map[name]["receive"]["value"].popleft()) * 8)
00046 
00047                 self.faces_map[name]["transmit"]["publisher"].publish(msg_transmit)
00048                 self.faces_map[name]["receive"]["publisher"].publish(msg_receive)
00049 
00050     def read_net_file(self):
00051         with open("/proc/net/dev") as f:
00052             status =  f.readlines()
00053         ret = []
00054         for s in status:
00055             match = self.match_face.match(s)
00056             if match:
00057                 nums = match.group(2).split()
00058                 ret.append([match.group(1).strip(), nums[8], nums[0]])
00059         return ret
00060 
00061 if __name__ == '__main__':
00062     NetworkStatus()


jsk_network_tools
Author(s): Yusuke Furuta
autogenerated on Sun Jan 25 2015 12:38:31