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