Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 import netifaces
00012 import rocon_python_wifi.iwlibs as pythonwifi
00013 import rospy
00014
00015 from gateway_msgs.msg import ConnectionStatistics
00016
00017
00018
00019
00020
00021
00022 class NetworkInterfaceManager(object):
00023
00024 '''
00025 Uses netifaces and pythonwifi to pull information about the network
00026 being used to connect to the hub
00027 '''
00028
00029 def __init__(self, interface_name=None):
00030 '''
00031 Initializes the interface manager. If the interface_name is None or an
00032 empty string, then the interface manager attempts to auto detect the
00033 interface being used.
00034 '''
00035 self.interface_name, self.interface_type = \
00036 self.detect_network_interface(interface_name)
00037
00038 def detect_network_interface(self, interface_name=''):
00039 '''
00040 Auto detects the network interface is none is supplied. If one is
00041 supplied, this function verifies that the interface is connected.
00042
00043 :returns: the interface name and type if detected successfully
00044 :rtype: (str, int8) or None
00045 '''
00046
00047 interfaces = []
00048
00049
00050 for interface in pythonwifi.getWNICnames():
00051 interfaces.append((interface, ConnectionStatistics.WIRELESS))
00052
00053
00054
00055 for inf in netifaces.interfaces():
00056 if inf in pythonwifi.getWNICnames():
00057 continue
00058 addrs = netifaces.ifaddresses(inf)
00059 if not netifaces.AF_INET in addrs:
00060 continue
00061 else:
00062 address = addrs[netifaces.AF_INET][0]['addr']
00063 if address.split('.')[0] == '127':
00064 continue
00065 interfaces.append((inf, ConnectionStatistics.WIRED))
00066
00067 for interface in interfaces:
00068 if interface[0] == interface_name:
00069 return interface[0], interface[1]
00070
00071 if interface_name:
00072 rospy.logwarn("Interface " + interface_name + " requested, but I " +
00073 " was unabled to find it on the system. I will try " +
00074 " and auto-detect the interface.")
00075
00076 if len(interfaces) == 0:
00077 rospy.logerr("Unable to auto detect a single interface. Cannot " +
00078 "send network information to hub.")
00079 return None, None
00080 elif len(interfaces) > 1:
00081 rospy.logerr("This machine is connected via multiple active " +
00082 "interfaces. Detected: " + str(interfaces) + ". Please " +
00083 "select a single interface using the network_interface " +
00084 "param (or environment variable GATEWAY_NETWORK_INTERFACE " +
00085 "if using the launcher). Cannot send network information to hub.")
00086 return None, None
00087
00088 return interfaces[0][0], interfaces[0][1]
00089
00090 def get_statistics(self):
00091 '''
00092 If the network interface manager is aware of which network interface
00093 was used to connect to the hub, then it prepares network statistics
00094 for that interface
00095
00096 @return network_statistics
00097 @rtype gateway_msgs.ConnectionStatistics
00098 '''
00099
00100 gateway_statistics = ConnectionStatistics()
00101 if not self.interface_name:
00102 gateway_statistics.network_info_available = False
00103 return gateway_statistics
00104 gateway_statistics.network_info_available = True
00105 gateway_statistics.network_type = self.interface_type
00106 if self.interface_type == ConnectionStatistics.WIRED:
00107 return gateway_statistics
00108
00109 try:
00110 wifi = pythonwifi.Wireless(self.interface_name)
00111 gateway_statistics.wireless_bitrate = \
00112 float(wifi.wireless_info.getBitrate().value)
00113 _, qual, _, _ = wifi.getStatistics()
00114 except IOError as e:
00115 rospy.logwarn("Gateway : not updating wireless statistics [wireless dropped out][%s]" % str(e))
00116 return gateway_statistics
00117
00118 gateway_statistics.wireless_link_quality = int(qual.quality)
00119
00120 gateway_statistics.wireless_signal_level = \
00121 float(qual.signallevel) - 256.0
00122 gateway_statistics.wireless_noise_level = float(qual.noiselevel)
00123
00124 return gateway_statistics