00001
00002
00003 from __future__ import with_statement
00004
00005 import roslib; roslib.load_manifest('multi_interface_roam')
00006 import rospy
00007 import std_msgs.msg
00008 import multi_interface_roam.multi_interface_roam as mir
00009 import multi_interface_roam.rosmasterless
00010 import sys
00011 import os
00012 import os.path
00013 import time
00014 import yaml
00015 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue, DiagnosticArray
00016 from pr2_msgs.msg import AccessPoint
00017
00018 freq_to_chan_map = {
00019 2412000000L : 1,
00020 2417000000L : 2,
00021 2422000000L : 3,
00022 2427000000L : 4,
00023 2432000000L : 5,
00024 2437000000L : 6,
00025 2442000000L : 7,
00026 2447000000L : 8,
00027 2452000000L : 9,
00028 2457000000L : 10,
00029 2462000000L : 11,
00030 2467000000L : 12,
00031 2472000000L : 13,
00032 2484000000L : 14,
00033 3657500000L : 131,
00034 3662500000L : 132,
00035 3660000000L : 132,
00036 3667500000L : 133,
00037 3665000000L : 133,
00038 3672500000L : 134,
00039 3670000000L : 134,
00040 3677500000L : 135,
00041 3682500000L : 136,
00042 3680000000L : 136,
00043 3687500000L : 137,
00044 3685000000L : 137,
00045 3689500000L : 138,
00046 3690000000L : 138,
00047 4915000000L : 183,
00048 4920000000L : 184,
00049 4925000000L : 185,
00050 4935000000L : 187,
00051 4940000000L : 188,
00052 4945000000L : 189,
00053 4960000000L : 192,
00054 4980000000L : 196,
00055 5035000000L : 7,
00056 5040000000L : 8,
00057 5045000000L : 9,
00058 5055000000L : 11,
00059 5060000000L : 12,
00060 5080000000L : 16,
00061 5170000000L : 34,
00062 5180000000L : 36,
00063 5190000000L : 38,
00064 5200000000L : 40,
00065 5210000000L : 42,
00066 5220000000L : 44,
00067 5230000000L : 46,
00068 5240000000L : 48,
00069 5260000000L : 52,
00070 5280000000L : 56,
00071 5300000000L : 60,
00072 5320000000L : 64,
00073 5500000000L : 100,
00074 5520000000L : 104,
00075 5540000000L : 108,
00076 5560000000L : 112,
00077 5580000000L : 116,
00078 5600000000L : 120,
00079 5620000000L : 124,
00080 5640000000L : 128,
00081 5660000000L : 132,
00082 5680000000L : 136,
00083 5700000000L : 140,
00084 5745000000L : 149,
00085 5765000000L : 153,
00086 5785000000L : 157,
00087 5805000000L : 161,
00088 5825000000L : 165,
00089 }
00090
00091 class MultiInterfaceDiagPublisher:
00092 def __init__(self, config_file):
00093 with open(config_file, 'r') as f:
00094 self.config = yaml.load(f.read())
00095 if 'wireless_namespace' in self.config:
00096 self.wireless_namespace = self.config['wireless_namespace']
00097 else:
00098 self.wireless_namespace = 'wifi'
00099
00100 try:
00101 mir.logdir = self.config['log_directory']
00102 except KeyError:
00103 pass
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116 self.diag_pub = rospy.Publisher("/diagnostics", DiagnosticArray)
00117 self.wifi_pub = rospy.Publisher(self.wireless_namespace+"/accesspoint", AccessPoint)
00118 wireless_interfaces = []
00119 interfaces = self.config['interfaces']
00120 for i in interfaces:
00121 if interfaces[i]['type'] == 'wireless':
00122 wireless_interfaces.append(i)
00123 self.wifi_sub_pub = dict((iface, rospy.Publisher(self.wireless_namespace+"/"+iface+"/accesspoint", AccessPoint)) for iface in wireless_interfaces)
00124
00125 self.hostname = os.uname()[1]
00126 print
00127 print "**************************************************************"
00128 print mir.log_time_string(time.time()), "restarting."
00129 print "**************************************************************"
00130 mir.main(config_file, mir.SimpleSelectionStrategy, self.publish_diags)
00131 print "**************************************************************"
00132 print "Exiting."
00133 print "**************************************************************"
00134 print
00135 rospy.signal_shutdown("main has exited")
00136
00137 @staticmethod
00138 def fill_diags(name, summary, hid, diags):
00139 ds = DiagnosticStatus()
00140 ds.values = [KeyValue(k, str(v)) for (k, v) in diags]
00141 ds.hardware_id = hid
00142 ds.name = rospy.get_caller_id().lstrip('/') + ": " + name
00143 ds.message = summary
00144 return ds
00145
00146 @staticmethod
00147 def frequency_to_channel(freq):
00148
00149 try:
00150 return freq_to_chan_map[freq]
00151 except:
00152 return -1
00153
00154 @staticmethod
00155 def gen_accesspoint_msg(iface):
00156 msg = AccessPoint()
00157 msg.essid = iface.essid
00158 msg.macaddr = iface.bssid
00159 msg.signal = iface.wifi_signal
00160 msg.noise = iface.wifi_noise
00161 msg.snr = msg.signal - msg.noise
00162 msg.quality = iface.wifi_quality
00163 msg.rate = iface.wifi_rate
00164 msg.tx_power = iface.wifi_txpower
00165 msg.channel = MultiInterfaceDiagPublisher.frequency_to_channel(iface.wifi_frequency)
00166 return msg
00167
00168 def publish_diags(self, strategy):
00169 now = rospy.get_rostime()
00170 ns = strategy.ns
00171 ds = self.fill_diags("synthetic interface", ns.diag_summary, self.hostname, strategy.ns.diags)
00172 ds.level = ns.diag_level
00173 statuses = [ds]
00174
00175 for i in range(0, len(ns.interfaces)):
00176 iface = ns.interfaces[i]
00177 ds = self.fill_diags(iface.iface, iface.diag_summary, self.hostname, iface.diags)
00178 statuses.append(ds)
00179 if iface.__class__ == mir.WirelessInterface:
00180 msg = self.gen_accesspoint_msg(iface)
00181 msg.header.stamp = now
00182 self.wifi_sub_pub[iface.iface].publish(msg)
00183 if i == ns.active_iface:
00184 self.wifi_pub.publish(msg)
00185
00186 da = DiagnosticArray()
00187 da.header.stamp = rospy.get_rostime()
00188 da.status = statuses
00189 self.diag_pub.publish(da)
00190
00191 if __name__ == "__main__":
00192 if len(sys.argv) != 2:
00193 print >> sys.stderr
00194 print >> sys.stderr, "usage: roam_node.py config_file.yaml"
00195 print >> sys.stderr
00196 print >> sys.stderr, "This node cannot presently be used with roslaunch as it will be confused by the __name and __log parameters."
00197 sys.exit(1)
00198
00199 rospy.init_node("multi_interface_roam", disable_rosout=True, disable_rostime=True, disable_signals=True)
00200
00201 MultiInterfaceDiagPublisher(sys.argv[1])