ddwrt.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import os, sys, string, time, getopt, re
19 import io
20 
21 import mechanize
22 import csv
23 import gc
24 
25 import rospy
26 from std_msgs.msg import Header
27 from cob_msgs.msg import AccessPoint, Network, SiteSurvey
28 
30  for item in gc.garbage:
31  if type(item) == dict:
32  for s in item.keys_iter():
33  del item[s]
34  del gc.garbage[:]
35 
36 class WifiAP:
37  def __init__(self, hostname, username, password):
38  self.hostname = hostname
39  self.username = username
40  self.password = password
41 
42  def newBrowser(self):
43  # Create new browsers all the time because its data structures grow
44  # unboundedly (texas#135)
45  br = mechanize.Browser()
46  #br.add_password(self.hostname, self.username, self.password)
47  #br.set_handle_robots(None)
48  return br
49 
50  def fetchSiteSurvey(self):
51  url = "http://%s/Site_Survey.asp" % self.hostname
52 
53  browser = self.newBrowser()
54  response = browser.open(url) # pylint: disable=assignment-from-none
55 
56  body = response.read()
57 
58  #make sure that we put a stamp on things
59  header = Header()
60  header.stamp = rospy.Time.now()
61  networks = []
62  survey = SiteSurvey(header, networks)
63 
64  lines = body.split("\n")
65  for i in range(len(lines)):
66  if lines[i].startswith("var table = "):
67  break
68 
69  aplines = []
70  for j in range(i+1, len(lines)):
71  if lines[j].startswith(");"): break
72  line = lines[j].strip()
73  if not line: continue
74  if line[0] == ",": line = line[1:]
75 
76  aplines.append(line)
77 
78  fp = io.StringIO('\n'.join(aplines))
79  reader = csv.reader(fp)
80  for row in reader:
81  essid = row[0]
82  macattr = row[2]
83  channel = row[3]
84  rssi = row[4]
85  noise = row[5]
86  beacon = row[6]
87 
88  network = Network(macattr, essid, channel, rssi, noise, beacon)
89  survey.networks.append(network)
90  return survey
91 
92  def fetchBandwidthStats(self, interface):
93  url = "http://%s/fetchif.cgi?%s" % (self.hostname, interface)
94 
95  browser = self.newBrowser()
96  response = browser.open(url) # pylint: disable=assignment-from-none
97  body = response.read()
98 
99  lines = body.split("\n")
100 
101  if len(lines) > 1:
102  line = lines[1].strip()
103  iparts = line.split(":", 1)
104  parts = iparts[1].split()
105  print(interface, parts)
106 
107 
108  def fetchCurrentAP(self):
109  url = "http://%s/Status_Wireless.live.asp" % self.hostname
110 
111  browser = self.newBrowser()
112  response = browser.open(url) # pylint: disable=assignment-from-none
113  body = response.read()
114 
115  line = None
116  lines = body.split("\n")
117 
118  d = {}
119  for line in lines:
120  line = line[1:-1]
121  line = line.replace(" ", "")
122  parts = line.split("::", 1)
123  if len(parts) == 2:
124  d[parts[0]] = parts[1]
125 
126  essid = d.get('wl_ssid', '')
127  wl_channel = d.get('wl_channel', '').split()[0]
128  channel = int(wl_channel)
129  rate = d.get('wl_rate', '')
130 
131  signal = None
132  noise = None
133  snr = None
134  quality = None
135 
136  tx_power = d.get('wl_xmit', '')
137 
138  active_wireless = d.get('active_wireless', None)
139  ap = None
140  if active_wireless:
141  active_wireless = active_wireless.replace("'", "")
142  parts = active_wireless.split(",")
143  macaddr = parts[0]
144  #interface = parts[1]
145  if len(parts) == 7:
146  signal = int(parts[4])
147  noise = int(parts[5])
148  snr = int(parts[6])
149  quality = signal * 1.24 + 116
150  else:
151  signal = int(parts[5])
152  noise = int(parts[6])
153  snr = int(parts[7])
154  quality = int(parts[8])/10
155 
156  #self.fetchBandwidthStats(interface)
157 
158  #make sure that we put a stamp on things
159  header = Header()
160  header.stamp = rospy.Time.now()
161 
162  ap = AccessPoint(header=header,
163  essid=essid,
164  macaddr=macaddr,
165  signal=signal,
166  noise=noise,
167  snr=snr,
168  channel=channel,
169  rate=rate,
170  quality=quality,
171  tx_power=tx_power)
172 
173  return ap
174 
175 
176 def loop():
177  rospy.init_node("wifi_ddwrt")
178 
179  router_ip = rospy.get_param('~router', 'wifi-router')
180  username = rospy.get_param('~username', 'root')
181  password = rospy.get_param('~password', '')
182 
183  ap = WifiAP(router_ip, username, password)
184 
185  pub1 = rospy.Publisher("ddwrt/sitesurvey", SiteSurvey, queue_size=50 )
186  pub2 = rospy.Publisher("ddwrt/accesspoint", AccessPoint, queue_size=50 )
187 
188  r = rospy.Rate(.5)
189  lastTime = 0
190  last_ex = ''
191  while not rospy.is_shutdown():
192  breakUpTrash() # Needed because mechanize leaves data structures that the GC sees as uncollectable (texas#135)
193  try:
194  if time.time() - lastTime > 60:
195  survey = ap.fetchSiteSurvey()
196  pub1.publish(survey)
197  lastTime = time.time()
198  node = ap.fetchCurrentAP()
199  if node: pub2.publish(node)
200  last_ex = ''
201  except Exception as e:
202  if e != last_ex:
203  rospy.logwarn("Caught exception %s" % e)
204  last_ex = e
205  r.sleep()
206 
207 def test():
208  router_ip = rospy.get_param('~router_ip', 'wifi-router')
209  username = rospy.get_param('~username', 'root')
210  password = rospy.get_param('~password', '')
211 
212  ap = WifiAP(router_ip, username, password)
213  while 1:
214  if 0:
215  survey = ap.fetchSiteSurvey()
216  print(survey)
217  if 1:
218  node = ap.fetchCurrentAP()
219  print(node)
220 
221 def usage(progname):
222  print(__doc__ % vars())
223 
224 def main(argv, stdout, environ):
225  progname = argv[0]
226  optlist, _ = getopt.getopt(argv[1:], "", ["help", "test",])
227 
228  testflag = 0
229 
230  for (field, _) in optlist:
231  if field == "--help":
232  usage(progname)
233  return
234  elif field == "--test":
235  testflag = 1
236 
237  if testflag:
238  test()
239  return
240 
241  loop()
242 
243 if __name__ == "__main__":
244  main(sys.argv, sys.stdout, os.environ)
245 
246 
def __init__(self, hostname, username, password)
Definition: ddwrt.py:37
def newBrowser(self)
Definition: ddwrt.py:42
def loop()
Definition: ddwrt.py:176
def fetchCurrentAP(self)
Definition: ddwrt.py:108
def fetchSiteSurvey(self)
Definition: ddwrt.py:50
def fetchBandwidthStats(self, interface)
Definition: ddwrt.py:92
def breakUpTrash()
Definition: ddwrt.py:29
def main(argv, stdout, environ)
Definition: ddwrt.py:224
def test()
Definition: ddwrt.py:207
def usage(progname)
Definition: ddwrt.py:221


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Wed Apr 7 2021 03:03:11