36 import os, sys, string, time, getopt, re
    41 from pr2_msgs.msg 
import AccessPoint
    43 from mechanize 
import Browser
    44 from std_msgs.msg 
import Header
    50     for item 
in gc.garbage:
    51         if type(item) == dict:
    52             for s 
in item.keys_iter():
    57   def __init__(self, hostname, username, password):
    67     br.set_handle_robots(
None)
    71     url = 
"http://%s/Site_Survey.asp" % self.
hostname    75     body = response.read()
    79     header.stamp = rospy.Time.now()
    81     survey = SiteSurvey(header, networks)
    83     lines = body.split(
"\n")
    84     for i 
in range(len(lines)):
    85       if lines[i].startswith(
"var table = "):
    89     for j 
in range(i+1, len(lines)):
    90       if lines[j].startswith(
");"): 
break    91       line = lines[j].strip()
    93       if line[0] == 
",": line = line[1:]
    97     fp = StringIO.StringIO(string.join(aplines, 
'\n'))
    98     reader = csv.reader(fp)
   102       channel = int(row[3])
   107       network = Network(macattr, essid, channel, rssi, noise, beacon)
   108       survey.networks.append(network)
   112     url = 
"http://%s/fetchif.cgi?%s" % (self.
hostname, interface)
   114     body = response.read()
   116     lines = body.split(
"\n")
   119       line = lines[1].strip()
   120       iparts = line.split(
":", 1)
   121       parts = iparts[1].split()
   122       print interface, parts
   126     url = 
"http://%s/Status_Wireless.live.asp" % self.
hostname   128     body = response.read()
   131     lines = body.split(
"\n")
   136       line = line.replace(
" ", 
"")
   137       parts = line.split(
"::", 1)
   139         d[parts[0]] = parts[1]
   141     essid = d.get(
'wl_ssid', 
'')
   142     wl_channel = d.get(
'wl_channel', 
'').split()[0]
   143     channel = int(wl_channel)
   144     rate = d.get(
'wl_rate', 
'')
   151     tx_power = d.get(
'wl_xmit', 
'')
   153     active_wireless = d.get(
'active_wireless', 
None)
   156       active_wireless = active_wireless.replace(
"'", 
"")
   157       parts = active_wireless.split(
",")
   161         signal = int(parts[4])
   162         noise = int(parts[5])
   164         quality = signal * 1.24 + 116
   166         signal = int(parts[5])
   167         noise = int(parts[6])
   169         quality = int(parts[8])/10
   175       header.stamp = rospy.Time.now()
   177       ap = AccessPoint(header=header,
   192   rospy.init_node(
"wifi_ddwrt")
   194   router_ip = rospy.get_param(
'~router', 
'wifi-router')
   195   username = rospy.get_param(
'~username', 
'root')
   196   password = rospy.get_param(
'~password', 
'')
   198   ap = 
WifiAP(router_ip, username, password)
   200   pub1 = rospy.Publisher(
"ddwrt/sitesurvey", SiteSurvey)
   201   pub2 = rospy.Publisher(
"ddwrt/accesspoint", AccessPoint)
   206   while not rospy.is_shutdown():
   209       if time.time() - lastTime > 60:
   210         survey = ap.fetchSiteSurvey()
   212         lastTime = time.time()
   213       node = ap.fetchCurrentAP()
   214       if node: pub2.publish(node)
   216     except Exception 
as e:
   218           rospy.logwarn(
"Caught exception %s" % e)
   223   router_ip = rospy.get_param(
'~router_ip', 
'wifi-router')
   224   username = rospy.get_param(
'~username', 
'root')
   225   password = rospy.get_param(
'~password', 
'')
   227   ap = 
WifiAP(router_ip, username, password)
   230       survey = ap.fetchSiteSurvey()
   233       node = ap.fetchCurrentAP()
   237   print __doc__ % vars()
   239 def main(argv, stdout, environ):
   241   optlist, args = getopt.getopt(argv[1:], 
"", [
"help", 
"test",])
   245   for (field, val) 
in optlist:
   246     if field == 
"--help":
   249     elif field == 
"--test":
   258 if __name__ == 
"__main__":
   259   main(sys.argv, sys.stdout, os.environ)
 def __init__(self, hostname, username, password)
 
def fetchSiteSurvey(self)
 
def fetchBandwidthStats(self, interface)
 
def main(argv, stdout, environ)