wifi_status.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2016, JSK Robotics Lab.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of the Willow Garage nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 ##\author Yuki Furuta
00036 ##\brief Monitors wifi status
00037 
00038 import re
00039 import subprocess
00040 import traceback
00041 
00042 import rospy
00043 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue, DiagnosticArray
00044 from jsk_network_tools.msg import WifiStatus
00045 
00046 def extract_number(s):
00047     try:
00048         extracted = re.match('^[0-9.-]*', s).group()
00049         try:
00050             return int(extracted)
00051         except ValueError:
00052             return float(extracted)
00053     except:
00054         return ''
00055 
00056 class Iwconfig(object):
00057     def __init__(self, dev):
00058         self.dev = dev
00059         self.status = {}
00060     def fetch(self):
00061         try:
00062             output = subprocess.check_output(["iwconfig", self.dev],
00063                                              stderr=subprocess.STDOUT)
00064         except subprocess.CalledProcessError as e:
00065             rospy.logdebug("iwconfig command return non-zero code: %s" % str(e.returncode))
00066             output = e.output
00067         for entity in re.split('\s{2,}', output.replace('=',':').replace('"','')):
00068             splitted = entity.split(':')
00069             if len(splitted) >= 2:
00070                 key = entity.split(':')[0].strip()
00071                 value = ":".join(entity.split(':')[1:]).strip()
00072                 if "Quality" in key:
00073                     q1, q2 = value.split('/')
00074                     value = str(float(q1) / float(q2))
00075                 self.status[key] = value
00076     def is_enabled(self):
00077         if "ESSID" not in self.status:
00078             return False
00079         else:
00080             return True
00081     def is_connected(self):
00082         if not self.is_enabled():
00083             return False
00084         elif "off" in self.status["ESSID"]:
00085             return False
00086         else:
00087             return True
00088 
00089 class NetworkStatusPublisherNode(object):
00090     def __init__(self):
00091         self.ifname = rospy.get_param("~network_interface", "wlan0")
00092         self.rate = rospy.get_param("~update_rate", 1.0)
00093         self.warn_quality = rospy.get_param("~warning_quality", 0.4)
00094         self.iwconfig = Iwconfig(self.ifname)
00095         self.status_pub = rospy.Publisher("~status", WifiStatus, queue_size=1)
00096         self.diagnostic_pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=1)
00097         self.poll_timer = rospy.Timer(rospy.Rate(self.rate).sleep_dur, self.poll)
00098     def poll(self, event=None):
00099         self.iwconfig.fetch()
00100         self.publish_status()
00101         self.publish_diagnostic()
00102     def publish_status(self):
00103         try:
00104             msg = WifiStatus()
00105             msg.header.stamp = rospy.Time.now()
00106             msg.interface = self.ifname
00107             msg.enabled = self.iwconfig.is_enabled()
00108             msg.connected = self.iwconfig.is_connected()
00109             if self.iwconfig.is_connected():
00110                 msg.ssid = self.iwconfig.status["ESSID"]
00111                 msg.frequency = extract_number(self.iwconfig.status["Frequency"])
00112                 msg.access_point = self.iwconfig.status["Access Point"]
00113                 msg.bitrate = extract_number(self.iwconfig.status["Bit Rate"])
00114                 msg.tx_power = extract_number(self.iwconfig.status["Tx-Power"])
00115                 msg.link_quality = extract_number(self.iwconfig.status["Link Quality"])
00116                 msg.signal_level = extract_number(self.iwconfig.status["Signal level"])
00117             self.status_pub.publish(msg)
00118         except Exception as e:
00119             rospy.logerr("Failed to publish status: %s" % str(e))
00120             rospy.logerr(traceback.format_exc())
00121     def publish_diagnostic(self):
00122         try:
00123             da = DiagnosticArray()
00124             ds = DiagnosticStatus()
00125             ds.name = rospy.get_caller_id().lstrip('/') + ': Status'
00126             ds.hardware_id = self.ifname
00127             if not self.iwconfig.is_enabled():
00128                 ds.level = DiagnosticStatus.STALE
00129                 ds.message = "Device not found"
00130             elif not self.iwconfig.is_connected():
00131                 ds.level = DiagnosticStatus.ERROR
00132                 ds.message = "No connection"
00133             else:
00134                 if extract_number(self.iwconfig.status["Link Quality"]) < self.warn_quality:
00135                     ds.level = DiagnosticStatus.WARN
00136                     ds.message = "Connected, but bad quality"
00137                 else:
00138                     ds.level = DiagnosticStatus.OK
00139                     ds.message = "Connected"
00140                 for key, val in self.iwconfig.status.items():
00141                     ds.values.append(KeyValue(key, val))
00142             da.status.append(ds)
00143             da.header.stamp = rospy.Time.now()
00144             self.diagnostic_pub.publish(da)
00145         except Exception as e:
00146             rospy.logerr('Failed to publish diagnostic: %s' % str(e))
00147             rospy.logerr(traceback.format_exc())
00148 
00149 if __name__ == '__main__':
00150     rospy.init_node("network_status")
00151     n = NetworkStatusPublisherNode()
00152     rospy.spin()


jsk_network_tools
Author(s): Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:47