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