18 import os, sys, string, time, getopt, re
    26 from std_msgs.msg 
import Header
    27 from cob_msgs.msg import AccessPoint, Network, SiteSurvey
    30     for item 
in gc.garbage:
    31         if type(item) == dict:
    32             for s 
in item.keys_iter():
    37   def __init__(self, hostname, username, password):
    45     br = mechanize.Browser()
    51     url = 
"http://%s/Site_Survey.asp" % self.
hostname    54     response = browser.open(url)  
    56     body = response.read()
    60     header.stamp = rospy.Time.now()
    62     survey = SiteSurvey(header, networks)
    64     lines = body.split(
"\n")
    65     for i 
in range(len(lines)):
    66       if lines[i].startswith(
"var table = "):
    70     for j 
in range(i+1, len(lines)):
    71       if lines[j].startswith(
");"): 
break    72       line = lines[j].strip()
    74       if line[0] == 
",": line = line[1:]
    78     fp = io.StringIO(
'\n'.join(aplines))
    79     reader = csv.reader(fp)
    88       network = Network(macattr, essid, channel, rssi, noise, beacon)
    89       survey.networks.append(network)
    93     url = 
"http://%s/fetchif.cgi?%s" % (self.
hostname, interface)
    96     response = browser.open(url)  
    97     body = response.read()
    99     lines = body.split(
"\n")
   102       line = lines[1].strip()
   103       iparts = line.split(
":", 1)
   104       parts = iparts[1].split()
   105       print(interface, parts)
   109     url = 
"http://%s/Status_Wireless.live.asp" % self.
hostname   112     response = browser.open(url)  
   113     body = response.read()
   116     lines = body.split(
"\n")
   121       line = line.replace(
" ", 
"")
   122       parts = line.split(
"::", 1)
   124         d[parts[0]] = parts[1]
   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', 
'')
   136     tx_power = d.get(
'wl_xmit', 
'')
   138     active_wireless = d.get(
'active_wireless', 
None)
   141       active_wireless = active_wireless.replace(
"'", 
"")
   142       parts = active_wireless.split(
",")
   146         signal = int(parts[4])
   147         noise = int(parts[5])
   149         quality = signal * 1.24 + 116
   151         signal = int(parts[5])
   152         noise = int(parts[6])
   154         quality = int(parts[8])/10
   160       header.stamp = rospy.Time.now()
   162       ap = AccessPoint(header=header,
   177   rospy.init_node(
"wifi_ddwrt")
   179   router_ip = rospy.get_param(
'~router', 
'wifi-router')
   180   username = rospy.get_param(
'~username', 
'root')
   181   password = rospy.get_param(
'~password', 
'')
   183   ap = 
WifiAP(router_ip, username, password)
   185   pub1 = rospy.Publisher(
"ddwrt/sitesurvey", SiteSurvey, queue_size=50 )
   186   pub2 = rospy.Publisher(
"ddwrt/accesspoint", AccessPoint, queue_size=50 )
   191   while not rospy.is_shutdown():
   194       if time.time() - lastTime > 60:
   195         survey = ap.fetchSiteSurvey()
   197         lastTime = time.time()
   198       node = ap.fetchCurrentAP()
   199       if node: pub2.publish(node)
   201     except Exception 
as e:
   203           rospy.logwarn(
"Caught exception %s" % e)
   208   router_ip = rospy.get_param(
'~router_ip', 
'wifi-router')
   209   username = rospy.get_param(
'~username', 
'root')
   210   password = rospy.get_param(
'~password', 
'')
   212   ap = 
WifiAP(router_ip, username, password)
   215       survey = ap.fetchSiteSurvey()
   218       node = ap.fetchCurrentAP()
   222   print(__doc__ % vars())
   224 def main(argv, stdout, environ):
   226   optlist, _ = getopt.getopt(argv[1:], 
"", [
"help", 
"test",])
   230   for (field, _) 
in optlist:
   231     if field == 
"--help":
   234     elif field == 
"--test":
   243 if __name__ == 
"__main__":
   244   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)