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 import random
00039
00040 import rospy
00041 from wifi_ddwrt.msg import *
00042 from pr2_msgs.msg import AccessPoint
00043
00044 from std_msgs.msg import Header
00045
00046 wifi_data = {"header": {"seq": 24, "stamp": 1257901832.6, "frame_id": "0"}, "networks": [{"macaddr": "00:18:F8:F9:6C:41", "essid": "willow", "channel": 11, "rssi": -35, "noise": -88, "beacon": 100}, {"macaddr": "00:18:F8:F9:6B:BD", "essid": "willow", "channel": 11, "rssi": -71, "noise": -88, "beacon": 100}, {"macaddr": "00:18:F8:F9:6C:1D", "essid": "willow", "channel": 1, "rssi": -70, "noise": -92, "beacon": 100}, {"macaddr": "00:30:44:03:1F:F9", "essid": "PRLAN", "channel": 1, "rssi": -73, "noise": -92, "beacon": 100}, {"macaddr": "00:30:44:03:1F:F4", "essid": "PRGLAN", "channel": 2, "rssi": -80, "noise": -89, "beacon": 100}, {"macaddr": "00:18:F8:F9:6C:4D", "essid": "willow", "channel": 6, "rssi": -81, "noise": -86, "beacon": 100}, {"macaddr": "00:18:F8:F9:6C:44", "essid": "willow", "channel": 6, "rssi": -79, "noise": -85, "beacon": 100}]}
00047
00048 def minmax(v, lower, upper):
00049 if v < lower: v = lower
00050 if v > upper: v = upper
00051 return v
00052
00053 class WifiAP:
00054 def __init__(self):
00055 self.ap = AccessPoint()
00056 self.t = time.time()
00057 self._pick_ap()
00058
00059 def _pick_ap(self):
00060 ap = random.choice(wifi_data['networks'])
00061 self.ap.macaddr = ap['macaddr']
00062 self.ap.channel = ap['channel']
00063 self.ap.essid = ap['essid']
00064 self.ap.rate = '54 Mbps'
00065 self.ap.tx_power = '71 mW'
00066 self.ap.signal = random.randint(-100, -48)
00067 self.ap.snr = 44
00068 self.ap.noise = -92
00069 self.ap.quality = 56
00070
00071 def _gen_snr(self):
00072 d = 2
00073 if time.time() - self.t > 20:
00074 d = 10
00075 self.ap.signal = minmax(self.ap.signal + random.randint(-d, d), -70, -20)
00076
00077 self.ap.snr = minmax(self.ap.snr + random.randint(-d, d), 30, 90)
00078 self.ap.noise = minmax(self.ap.noise + random.randint(-d, d), -95, -30)
00079 self.ap.quality = int(self.ap.signal * 1.24 + 116)
00080
00081 def fetchSiteSurvey(self):
00082 header = Header()
00083 header.stamp = rospy.Time.now()
00084 networks = []
00085 survey = SiteSurvey(header, networks)
00086
00087 for network in wifi_data["networks"]:
00088 network = Network(network['macaddr'], network['essid'], network['channel'], network['rssi'], network['noise'], network['beacon'])
00089 survey.networks.append(network)
00090 return survey
00091
00092 def fetchCurrentAP(self):
00093 if time.time() - self.t > 60:
00094 self._pick_ap()
00095 self._gen_snr()
00096
00097
00098 self.ap.header = Header()
00099 self.ap.header.stamp = rospy.Time.now()
00100
00101 return self.ap
00102
00103 def loop():
00104 rospy.init_node("wifi_ddwrt")
00105
00106 ap = WifiAP()
00107
00108 pub1 = rospy.Publisher("ddwrt/sitesurvey", SiteSurvey)
00109 pub2 = rospy.Publisher("ddwrt/accesspoint", AccessPoint)
00110
00111 while not rospy.is_shutdown():
00112 survey = ap.fetchSiteSurvey()
00113 pub1.publish(survey)
00114 node = ap.fetchCurrentAP()
00115 pub2.publish(node)
00116 time.sleep(5)
00117
00118 def usage(progname):
00119 print __doc__ % vars()
00120
00121 def main(argv, stdout, environ):
00122 progname = argv[0]
00123 optlist, args = getopt.getopt(argv[1:], "", ["help",])
00124
00125 for (field, val) in optlist:
00126 if field == "--help":
00127 usage(progname)
00128 return
00129
00130 loop()
00131
00132 if __name__ == "__main__":
00133 main(sys.argv, sys.stdout, os.environ)
00134
00135