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 
00033 
00034 
00035 
00036 import os, sys, string, time, getopt, re
00037 import StringIO
00038 
00039 import rospy
00040 from wifi_ddwrt.msg import *
00041 from pr2_msgs.msg import AccessPoint
00042 
00043 from mechanize import Browser
00044 from std_msgs.msg import Header
00045 import csv
00046 
00047 import gc
00048 
00049 def breakUpTrash():
00050     for item in gc.garbage:
00051         if type(item) == dict:
00052             for s in item.keys_iter():
00053                 del item[s]
00054         del gc.garbage[:]
00055 
00056 class WifiAP:
00057   def __init__(self, hostname, username, password):
00058     self.hostname = hostname
00059     self.username = username
00060     self.password = password
00061 
00062   def newBrowser(self):
00063     
00064     
00065     br = Browser()
00066     br.add_password(self.hostname, self.username, self.password)
00067     br.set_handle_robots(None)
00068     return br
00069 
00070   def fetchSiteSurvey(self):
00071     url = "http://%s/Site_Survey.asp" % self.hostname
00072 
00073     response = self.newBrowser().open(url)
00074 
00075     body = response.read()
00076     
00077     
00078     header = Header()
00079     header.stamp = rospy.Time.now()
00080     networks = []
00081     survey = SiteSurvey(header, networks)
00082 
00083     lines = body.split("\n")
00084     for i in range(len(lines)):
00085       if lines[i].startswith("var table = "):
00086         break
00087 
00088     aplines = []
00089     for j in range(i+1, len(lines)):
00090       if lines[j].startswith(");"): break
00091       line = lines[j].strip()
00092       if not line: continue
00093       if line[0] == ",": line = line[1:]
00094 
00095       aplines.append(line)
00096 
00097     fp = StringIO.StringIO(string.join(aplines, '\n'))
00098     reader = csv.reader(fp)
00099     for row in reader:
00100       essid = row[0]
00101       macattr = row[2]
00102       channel = int(row[3])
00103       rssi = int(row[4])
00104       noise = int(row[5])
00105       beacon = int(row[6])
00106 
00107       network = Network(macattr, essid, channel, rssi, noise, beacon)
00108       survey.networks.append(network)
00109     return survey
00110 
00111   def fetchBandwidthStats(self, interface):
00112     url = "http://%s/fetchif.cgi?%s" % (self.hostname, interface)
00113     response = self.newBrowser().open(url)
00114     body = response.read()
00115 
00116     lines = body.split("\n")
00117 
00118     if len(lines) > 1:
00119       line = lines[1].strip()
00120       iparts = line.split(":", 1)
00121       parts = iparts[1].split()
00122       print interface, parts
00123       
00124 
00125   def fetchCurrentAP(self):
00126     url = "http://%s/Status_Wireless.live.asp" % self.hostname
00127     response = self.newBrowser().open(url)
00128     body = response.read()
00129 
00130     line = None
00131     lines = body.split("\n")
00132 
00133     d = {}
00134     for line in lines:
00135       line = line[1:-1]
00136       line = line.replace(" ", "")
00137       parts = line.split("::", 1)
00138       if len(parts) == 2:
00139         d[parts[0]] = parts[1]
00140       
00141     essid = d.get('wl_ssid', '')
00142     wl_channel = d.get('wl_channel', '').split()[0]
00143     channel = int(wl_channel)
00144     rate = d.get('wl_rate', '')
00145     
00146     signal = None
00147     noise = None
00148     snr = None
00149     quality = None
00150 
00151     tx_power = d.get('wl_xmit', '')
00152 
00153     active_wireless = d.get('active_wireless', None)
00154     ap = None
00155     if active_wireless:
00156       active_wireless = active_wireless.replace("'", "")
00157       parts = active_wireless.split(",")
00158       macaddr = parts[0]
00159       interface = parts[1]
00160       if len(parts) == 7:
00161         signal = int(parts[4])
00162         noise = int(parts[5])
00163         snr = int(parts[6])
00164         quality = signal * 1.24 + 116
00165       else:
00166         signal = int(parts[5])
00167         noise = int(parts[6])
00168         snr = int(parts[7])
00169         quality = int(parts[8])/10
00170       
00171       
00172 
00173       
00174       header = Header()
00175       header.stamp = rospy.Time.now()
00176 
00177       ap = AccessPoint(header=header,
00178                        essid=essid,
00179                        macaddr=macaddr,
00180                        signal=signal,
00181                        noise=noise,
00182                        snr=snr,
00183                        channel=channel,
00184                        rate=rate,
00185                        quality=quality,
00186                        tx_power=tx_power)
00187 
00188     return ap
00189 
00190 
00191 def loop():
00192   rospy.init_node("wifi_ddwrt")
00193 
00194   router_ip = rospy.get_param('~router', 'wifi-router')
00195   username = rospy.get_param('~username', 'root')
00196   password = rospy.get_param('~password', '')
00197 
00198   ap = WifiAP(router_ip, username, password)
00199 
00200   pub1 = rospy.Publisher("ddwrt/sitesurvey", SiteSurvey)
00201   pub2 = rospy.Publisher("ddwrt/accesspoint", AccessPoint)
00202 
00203   r = rospy.Rate(.5)
00204   lastTime = 0
00205   last_ex = ''
00206   while not rospy.is_shutdown():
00207     breakUpTrash() 
00208     try:
00209       if time.time() - lastTime > 60:
00210         survey = ap.fetchSiteSurvey()
00211         pub1.publish(survey)
00212         lastTime = time.time()
00213       node = ap.fetchCurrentAP()
00214       if node: pub2.publish(node)
00215       last_ex = ''
00216     except Exception as e:
00217       if e != last_ex:
00218           rospy.logwarn("Caught exception %s" % e)
00219       last_ex = e
00220     r.sleep()
00221         
00222 def test():
00223   router_ip = rospy.get_param('~router_ip', 'wifi-router')
00224   username = rospy.get_param('~username', 'root')
00225   password = rospy.get_param('~password', '')
00226 
00227   ap = WifiAP(router_ip, username, password)
00228   while 1:
00229     if 0:
00230       survey = ap.fetchSiteSurvey()
00231       print survey
00232     if 1:
00233       node = ap.fetchCurrentAP()
00234       print node
00235 
00236 def usage(progname):
00237   print __doc__ % vars()
00238 
00239 def main(argv, stdout, environ):
00240   progname = argv[0]
00241   optlist, args = getopt.getopt(argv[1:], "", ["help", "test",])
00242 
00243   testflag = 0
00244 
00245   for (field, val) in optlist:
00246     if field == "--help":
00247       usage(progname)
00248       return
00249     elif field == "--test":
00250       testflag = 1
00251 
00252   if testflag:
00253     test()
00254     return
00255 
00256   loop()
00257 
00258 if __name__ == "__main__":
00259   main(sys.argv, sys.stdout, os.environ)
00260         
00261