wifi_status.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2016, JSK Robotics Lab.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 ##\author Yuki Furuta
36 ##\brief Monitors wifi status
37 
38 import re
39 import subprocess
40 import traceback
41 
42 import rospy
43 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue, DiagnosticArray
44 from jsk_network_tools.msg import WifiStatus
45 
47  try:
48  extracted = re.match('^[0-9.-]*', s).group()
49  try:
50  return int(extracted)
51  except ValueError:
52  return float(extracted)
53  except:
54  return ''
55 
56 class Iwconfig(object):
57  def __init__(self, dev):
58  self.dev = dev
59  self.status = {}
60  def fetch(self):
61  try:
62  output = subprocess.check_output(["iwconfig", self.dev],
63  stderr=subprocess.STDOUT)
64  except subprocess.CalledProcessError as e:
65  rospy.logdebug("iwconfig command return non-zero code: %s" % str(e.returncode))
66  output = e.output
67  for entity in re.split('\s{2,}', output.replace('=',':').replace('"','')):
68  splitted = entity.split(':')
69  if len(splitted) >= 2:
70  key = entity.split(':')[0].strip()
71  value = ":".join(entity.split(':')[1:]).strip()
72  if "Quality" in key:
73  q1, q2 = value.split('/')
74  value = str(float(q1) / float(q2))
75  self.status[key] = value
76  def is_enabled(self):
77  if "ESSID" not in self.status:
78  return False
79  else:
80  return True
81  def is_connected(self):
82  if not self.is_enabled():
83  return False
84  elif "off" in self.status["ESSID"]:
85  return False
86  else:
87  return True
88 
90  def __init__(self):
91  self.ifname = rospy.get_param("~network_interface", "wlan0")
92  self.rate = rospy.get_param("~update_rate", 1.0)
93  self.warn_quality = rospy.get_param("~warning_quality", 0.4)
94  self.iwconfig = Iwconfig(self.ifname)
95  self.status_pub = rospy.Publisher("~status", WifiStatus, queue_size=1)
96  self.diagnostic_pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=1)
97  self.poll_timer = rospy.Timer(rospy.Rate(self.rate).sleep_dur, self.poll)
98  def poll(self, event=None):
99  self.iwconfig.fetch()
100  self.publish_status()
101  self.publish_diagnostic()
102  def publish_status(self):
103  try:
104  msg = WifiStatus()
105  msg.header.stamp = rospy.Time.now()
106  msg.interface = self.ifname
107  msg.enabled = self.iwconfig.is_enabled()
108  msg.connected = self.iwconfig.is_connected()
109  if self.iwconfig.is_connected():
110  msg.ssid = self.iwconfig.status["ESSID"]
111  msg.frequency = extract_number(self.iwconfig.status["Frequency"])
112  msg.access_point = self.iwconfig.status["Access Point"]
113  msg.bitrate = extract_number(self.iwconfig.status["Bit Rate"])
114  msg.tx_power = extract_number(self.iwconfig.status["Tx-Power"])
115  msg.link_quality = extract_number(self.iwconfig.status["Link Quality"])
116  msg.signal_level = extract_number(self.iwconfig.status["Signal level"])
117  self.status_pub.publish(msg)
118  except Exception as e:
119  rospy.logerr("Failed to publish status: %s" % str(e))
120  rospy.logerr(traceback.format_exc())
122  try:
123  da = DiagnosticArray()
124  ds = DiagnosticStatus()
125  ds.name = rospy.get_caller_id().lstrip('/') + ': Status'
126  ds.hardware_id = self.ifname
127  if not self.iwconfig.is_enabled():
128  ds.level = DiagnosticStatus.STALE
129  ds.message = "Device not found"
130  elif not self.iwconfig.is_connected():
131  ds.level = DiagnosticStatus.ERROR
132  ds.message = "No connection"
133  else:
134  if extract_number(self.iwconfig.status["Link Quality"]) < self.warn_quality:
135  ds.level = DiagnosticStatus.WARN
136  ds.message = "Connected, but bad quality"
137  else:
138  ds.level = DiagnosticStatus.OK
139  ds.message = "Connected"
140  for key, val in self.iwconfig.status.items():
141  ds.values.append(KeyValue(key, val))
142  da.status.append(ds)
143  da.header.stamp = rospy.Time.now()
144  self.diagnostic_pub.publish(da)
145  except Exception as e:
146  rospy.logerr('Failed to publish diagnostic: %s' % str(e))
147  rospy.logerr(traceback.format_exc())
148 
149 if __name__ == '__main__':
150  rospy.init_node("network_status")
152  rospy.spin()
def is_enabled(self)
Definition: wifi_status.py:76
def __init__(self, dev)
Definition: wifi_status.py:57
def is_connected(self)
Definition: wifi_status.py:81
def extract_number(s)
Definition: wifi_status.py:46


jsk_network_tools
Author(s): Yusuke Furuta
autogenerated on Tue Feb 6 2018 03:45:07