Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 import roslib
00033 roslib.load_manifest('elektron_monitor')
00034 
00035 import rospy
00036 import diagnostic_msgs.msg
00037 
00038 import subprocess
00039 import re
00040 
00041 def wifi_monitor():
00042     """ 
00043     Function for retrieving information about wireless network interfaces,
00044     publishing signal power and noise ratios, IP address etc. 
00045     """
00046     
00047     diag_pub = rospy.Publisher('/diagnostics', diagnostic_msgs.msg.DiagnosticArray)
00048     rospy.init_node('wifi_monitor')
00049     while not rospy.is_shutdown():
00050         
00051         
00052         diag = diagnostic_msgs.msg.DiagnosticArray()
00053         diag.header.stamp = rospy.Time.now()
00054 
00055         lines = open("/proc/net/wireless", "r").readlines()
00056 
00057         faces = {}
00058         for line in lines[2:]:
00059             if line.find(":") < 0: continue
00060             face, data = line.split(":")
00061             strs = data.split()
00062             link = float(strs[1])
00063             level = float(strs[2])
00064             noise = float(strs[3])
00065             face = face.strip()
00066         
00067             p1 = subprocess.Popen(["ifconfig", face], stdout=subprocess.PIPE)
00068             p2 = subprocess.Popen(["grep", "inet addr"], stdin=p1.stdout, stdout=subprocess.PIPE)
00069             p3 = subprocess.Popen(["awk", "-F:", "{print $2}"], stdin=p2.stdout, stdout=subprocess.PIPE)
00070             p4 = subprocess.Popen(["awk",  "{print $1}"], stdin=p3.stdout, stdout=subprocess.PIPE)
00071             
00072             p1.stdout.close()  
00073             p2.stdout.close()  
00074             p3.stdout.close()  
00075             output = p4.communicate()[0]
00076         
00077             
00078             
00079             output = subprocess.Popen(['ifconfig', face], stdout=subprocess.PIPE).communicate()[0]
00080             ret = re.findall('inet addr:([^ ]*) ', output)
00081             if (len(ret) > 0):
00082                 ip = ret[0]
00083             else:
00084                 ip = "not connected"  
00085         
00086             
00087         
00088             
00089             stat = diagnostic_msgs.msg.DiagnosticStatus()
00090             stat.name = face
00091             stat.level = diagnostic_msgs.msg.DiagnosticStatus.OK
00092             stat.message = "OK"
00093         
00094 
00095             stat.values.append(diagnostic_msgs.msg.KeyValue("Quality", str(link)))
00096             stat.values.append(diagnostic_msgs.msg.KeyValue("Level", str(level)))
00097             stat.values.append(diagnostic_msgs.msg.KeyValue("Noise", str(noise)))
00098             stat.values.append(diagnostic_msgs.msg.KeyValue("IP", ip))
00099 
00100             
00101             diag.status.append(stat)
00102         
00103         
00104         diag_pub.publish(diag)
00105         rospy.sleep(2.0)
00106 
00107 
00108 if __name__ == '__main__':
00109     try:
00110         wifi_monitor()
00111     except rospy.ROSInterruptException: pass
00112     except IOError: pass
00113     except KeyError: pass