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