network_interface_manager.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # License: BSD
4 # https://raw.github.com/robotics-in-concert/rocon_multimaster/license/LICENSE
5 #
6 
7 ###############################################################################
8 # Imports
9 ###############################################################################
10 
11 import netifaces
12 import os
13 import rocon_python_wifi.iwlibs as pythonwifi
14 import rospy
15 
16 from gateway_msgs.msg import ConnectionStatistics
17 
18 ###############################################################################
19 # Thread
20 ###############################################################################
21 
22 
24 
25  '''
26  Uses netifaces and pythonwifi to pull information about the network
27  being used to connect to the hub
28  '''
29 
30  def __init__(self, interface_name=None):
31  '''
32  We have three means of getting the network interface that sits between
33  gateway and a hub - by input arg, by environment variable, or if these
34  are not specified, it tries to autodetect (but this only currently works
35  if there is just one interface).
36  '''
37  if interface_name is None or not interface_name:
38  # try and get from environment variable (this returns None if not found)
39  interface_name = os.environ.get('GATEWAY_NETWORK_INTERFACE')
40 
41  self.interface_name, self.interface_type = \
42  self.detect_network_interface(interface_name)
43 
44  def detect_network_interface(self, interface_name=''):
45  '''
46  Auto detects the network interface is none is supplied. If one is
47  supplied, this function verifies that the interface is connected.
48 
49  :returns: the interface name and type if detected successfully
50  :rtype: (str, int8) or None
51  '''
52 
53  interfaces = []
54 
55  # Detect wireless interfaces first
56  for interface in pythonwifi.getWNICnames():
57  interfaces.append((interface, ConnectionStatistics.WIRELESS))
58 
59  # Detect wired network interfaces. This command also detects wireless
60  # ones. Don't add them again
61  for inf in netifaces.interfaces():
62  if inf in pythonwifi.getWNICnames():
63  continue
64  addrs = netifaces.ifaddresses(inf)
65  if not netifaces.AF_INET in addrs:
66  continue
67  else:
68  address = addrs[netifaces.AF_INET][0]['addr']
69  if address.split('.')[0] == '127':
70  continue
71  interfaces.append((inf, ConnectionStatistics.WIRED))
72 
73  for interface in interfaces:
74  if interface[0] == interface_name:
75  return interface[0], interface[1]
76 
77  if interface_name:
78  rospy.logwarn("Interface " + interface_name + " requested, but I " +
79  " was unabled to find it on the system. I will try " +
80  " and auto-detect the interface.")
81 
82  if len(interfaces) == 0:
83  rospy.logerr("Unable to auto detect a single interface. Cannot " +
84  "send network information to hub.")
85  return None, None
86  elif len(interfaces) > 1:
87  rospy.logwarn("This machine is connected via multiple active " +
88  "interfaces. Detected: " + str(interfaces) + ". Please " +
89  "select a single interface using the network_interface " +
90  "param (or environment variable GATEWAY_NETWORK_INTERFACE " +
91  "if using the launcher). Cannot send network information to hub.")
92  return None, None
93 
94  return interfaces[0][0], interfaces[0][1]
95 
96  def get_statistics(self):
97  '''
98  If the network interface manager is aware of which network interface
99  was used to connect to the hub, then it prepares network statistics
100  for that interface
101 
102  @return network_statistics
103  @rtype gateway_msgs.ConnectionStatistics
104  '''
105 
106  gateway_statistics = ConnectionStatistics()
107  if not self.interface_name:
108  gateway_statistics.network_info_available = False
109  return gateway_statistics
110  gateway_statistics.network_info_available = True
111  gateway_statistics.network_type = self.interface_type
112  if self.interface_type == ConnectionStatistics.WIRED:
113  return gateway_statistics
114 
115  try:
116  wifi = pythonwifi.Wireless(self.interface_name)
117  gateway_statistics.wireless_bitrate = \
118  float(wifi.wireless_info.getBitrate().value) # Raw bitrate
119  _, qual, _, _ = wifi.getStatistics()
120  except IOError as e:
121  rospy.logwarn("Gateway : not updating wireless statistics [wireless dropped out][%s]" % str(e))
122  return gateway_statistics
123 
124  gateway_statistics.wireless_link_quality = int(qual.quality)
125  # The -256 is a hack. The value returned by pythonwifi seems to be off.
126  gateway_statistics.wireless_signal_level = \
127  float(qual.signallevel) - 256.0
128  gateway_statistics.wireless_noise_level = float(qual.noiselevel)
129 
130  return gateway_statistics


rocon_gateway
Author(s): Daniel Stonier , Jihoon Lee , Piyush Khandelwal
autogenerated on Mon Jun 10 2019 14:40:10