wifi_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2011, Robot Control and Pattern Recognition Group, Warsaw University of Technology
00006 #
00007 # All rights reserved.
00008 # 
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions are met:
00011 #     * Redistributions of source code must retain the above copyright
00012 #       notice, this list of conditions and the following disclaimer.
00013 #     * Redistributions in binary form must reproduce the above copyright
00014 #       notice, this list of conditions and the following disclaimer in the
00015 #       documentation and/or other materials provided with the distribution.
00016 #     * Neither the name of the <organization> nor the
00017 #       names of its contributors may be used to endorse or promote products
00018 #       derived from this software without specific prior written permission.
00019 # 
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00023 # DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00024 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00025 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00026 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00027 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00028 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00029 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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         #Main header
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()  # Allow p1 to receive a SIGPIPE if p2 exits.
00073             p2.stdout.close()  # Allow p1 to receive a SIGPIPE if p3 exits.
00074             p3.stdout.close()  # Allow p1 to receive a SIGPIPE if p4 exits.
00075             output = p4.communicate()[0]
00076         
00077             #rospy.logwarn("Output: %s"%output)   
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             #rospy.logwarn("Output: %s"%ip)
00087         
00088             #interface info                                                                                                                              
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             #append
00101             diag.status.append(stat)
00102         
00103         #publish
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
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


elektron_monitor
Author(s): Maciej Stefanczyk
autogenerated on Thu Nov 14 2013 11:56:01