net_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 ############################################################################
00003 #    Copyright (C) 2009, Willow Garage, Inc.                               #
00004 #    Copyright (C) 2013 by Ralf Kaestner                                   #
00005 #    ralf.kaestner@gmail.com                                               #
00006 #    Copyright (C) 2013 by Jerome Maye                                     #
00007 #    jerome.maye@mavt.ethz.ch                                              #
00008 #                                                                          #
00009 #    All rights reserved.                                                  #
00010 #                                                                          #
00011 #    Redistribution and use in source and binary forms, with or without    #
00012 #    modification, are permitted provided that the following conditions    #
00013 #    are met:                                                              #
00014 #                                                                          #
00015 #    1. Redistributions of source code must retain the above copyright     #
00016 #       notice, this list of conditions and the following disclaimer.      #
00017 #                                                                          #
00018 #    2. Redistributions in binary form must reproduce the above copyright  #
00019 #       notice, this list of conditions and the following disclaimer in    #
00020 #       the documentation and/or other materials provided with the         #
00021 #       distribution.                                                      #
00022 #                                                                          #
00023 #    3. The name of the copyright holders may be used to endorse or        #
00024 #       promote products derived from this software without specific       #
00025 #       prior written permission.                                          #
00026 #                                                                          #
00027 #    THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS   #
00028 #    "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT     #
00029 #    LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS     #
00030 #    FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE        #
00031 #    COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,  #
00032 #    INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,  #
00033 #    BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;      #
00034 #    LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER      #
00035 #    CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT    #
00036 #    LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN     #
00037 #    ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE       #
00038 #    POSSIBILITY OF SUCH DAMAGE.                                           #
00039 ############################################################################
00040 
00041 # copied from https://github.com/ethz-asl/ros-system-monitor
00042 
00043 from __future__ import with_statement
00044 
00045 import rospy
00046 
00047 import traceback
00048 import threading
00049 from threading import Timer
00050 import sys, os, time
00051 from time import sleep
00052 import subprocess
00053 import string
00054 import re
00055 
00056 import socket
00057 
00058 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00059 
00060 stat_dict = {0: 'OK', 1: 'Warning', 2: 'Error'}
00061 
00062 def get_sys_net_stat(iface, sys):
00063   cmd = 'cat /sys/class/net/%s/statistics/%s' %(iface, sys)
00064   p = subprocess.Popen(cmd,
00065                        stdout = subprocess.PIPE,
00066                        stderr = subprocess.PIPE, shell = True)
00067   stdout, stderr = p.communicate()
00068   return (p.returncode, stdout.strip())
00069 
00070 def get_sys_net(iface, sys):
00071   cmd = 'cat /sys/class/net/%s/%s' %(iface, sys)
00072   p = subprocess.Popen(cmd,
00073                        stdout = subprocess.PIPE,
00074                        stderr = subprocess.PIPE, shell = True)
00075   stdout, stderr = p.communicate()
00076   return (p.returncode, stdout.strip())
00077 
00078 class NetMonitor():
00079   def __init__(self):
00080     rospy.init_node("net_monitor")
00081     self._mutex = threading.Lock()
00082     self._diag_hostname = rospy.get_param('~diag_hostname', "localhost")
00083     self._net_level_warn = rospy.get_param('~net_level_warn', 0.95)
00084     self._net_capacity = rospy.get_param('~net_capacity', 128)
00085     self._usage_stat = DiagnosticStatus()
00086     self._usage_stat.name = '%s Network Usage' % self._diag_hostname
00087     self._usage_stat.hardware_id = self._diag_hostname
00088     self._usage_stat.level = DiagnosticStatus.OK
00089     self._usage_stat.message = 'No Data'
00090 
00091     self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size = 1)
00092     self._usage_timer = rospy.Timer(rospy.Duration(1.0), self.check_usage)
00093     self._diag_timer = rospy.Timer(rospy.Duration(1.0), self.publish_stats)
00094 
00095   def check_network(self):
00096     values = []
00097     net_dict = {0: 'OK', 1: 'High Network Usage', 2: 'Network Down', 3: 'Call Error'}
00098     try:
00099       p = subprocess.Popen('ifstat -q -S 1 1',
00100                            stdout = subprocess.PIPE,
00101                            stderr = subprocess.PIPE, shell = True)
00102       stdout, stderr = p.communicate()
00103       retcode = p.returncode
00104       if retcode != 0:
00105         values.append(KeyValue(key = "\"ifstat -q -S 1 1\" Call Error",
00106           value = str(retcode)))
00107         return DiagnosticStatus.ERROR, net_dict[3], values
00108       rows = stdout.split('\n')
00109       data = rows[0].split()
00110       ifaces = []
00111       for i in range(0, len(data)):
00112         ifaces.append(data[i])
00113       data = rows[2].split()
00114       kb_in = []
00115       kb_out = []
00116       for i in range(0, len(data), 2):
00117         kb_in.append(data[i])
00118         kb_out.append(data[i + 1])
00119       level = DiagnosticStatus.OK
00120       for i in range(0, len(ifaces)):
00121         values.append(KeyValue(key = str(i), value = "======================="))
00122         values.append(KeyValue(key = 'Interface Name',
00123           value = ifaces[i]))
00124         (retcode, cmd_out) = get_sys_net(ifaces[i], 'operstate')
00125         if retcode == 0:
00126           values.append(KeyValue(key = 'State', value = cmd_out))
00127           ifacematch = re.match('eth[0-9]+', ifaces[i]) or re.match('eno[0-9]+', ifaces[i])
00128           if ifacematch and (cmd_out == 'down' or cmd_out == 'dormant'):
00129             level = DiagnosticStatus.ERROR
00130         values.append(KeyValue(key = 'Input Traffic',
00131           value = str(float(kb_in[i]) / 1024) + " (MB/s)"))
00132         values.append(KeyValue(key = 'Output Traffic',
00133           value = str(float(kb_out[i]) / 1024) + " (MB/s)"))
00134         net_usage_in = float(kb_in[i]) / 1024 / self._net_capacity
00135         net_usage_out = float(kb_out[i]) / 1024 / self._net_capacity
00136         if net_usage_in > self._net_level_warn or\
00137           net_usage_out > self._net_level_warn:
00138           level = DiagnosticStatus.WARN
00139         (retcode, cmd_out) = get_sys_net(ifaces[i], 'mtu')
00140         if retcode == 0:
00141           values.append(KeyValue(key = 'MTU', value = cmd_out))
00142         #additional keys (https://www.kernel.org/doc/Documentation/ABI/testing/sysfs-class-net-statistics)
00143         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_bytes')
00144         if retcode == 0:
00145           values.append(KeyValue(key = 'Total received MB',
00146             value = str(float(cmd_out) / 1024 / 1024)))
00147         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_bytes')
00148         if retcode == 0:
00149           values.append(KeyValue(key = 'Total transmitted MB',
00150             value = str(float(cmd_out) / 1024 / 1024)))
00151         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'collisions')
00152         if retcode == 0:
00153           values.append(KeyValue(key = 'collisions', value = cmd_out))
00154         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_errors')
00155         if retcode == 0:
00156           values.append(KeyValue(key = 'rx_errors', value = cmd_out))
00157         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_crc_errors')
00158         if retcode == 0:
00159           values.append(KeyValue(key = 'rx_crc_errors', value = cmd_out))
00160         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_dropped')
00161         if retcode == 0:
00162           values.append(KeyValue(key = 'rx_dropped', value = cmd_out))
00163         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_fifo_errors')
00164         if retcode == 0:
00165           values.append(KeyValue(key = 'rx_fifo_errors', value = cmd_out))
00166         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_frame_errors')
00167         if retcode == 0:
00168           values.append(KeyValue(key = 'rx_frame_errors', value = cmd_out))
00169         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_length_errors')
00170         if retcode == 0:
00171           values.append(KeyValue(key = 'rx_length_errors', value = cmd_out))
00172         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_missed_errors')
00173         if retcode == 0:
00174           values.append(KeyValue(key = 'rx_missed_errors', value = cmd_out))
00175         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_over_errors')
00176         if retcode == 0:
00177           values.append(KeyValue(key = 'rx_over_errors', value = cmd_out))
00178         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'rx_packets')
00179         if retcode == 0:
00180           values.append(KeyValue(key = 'rx_packets', value = cmd_out))
00181         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_errors')
00182         if retcode == 0:
00183           values.append(KeyValue(key = 'tx_errors', value = cmd_out))
00184         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_aborted_errors')
00185         if retcode == 0:
00186           values.append(KeyValue(key = 'tx_aborted_errors', value = cmd_out))
00187         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_carrier_errors')
00188         if retcode == 0:
00189           values.append(KeyValue(key = 'tx_carrier_errors', value = cmd_out))
00190         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_fifo_errors')
00191         if retcode == 0:
00192           values.append(KeyValue(key = 'tx_fifo_errors', value = cmd_out))
00193         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_heartbeat_errors')
00194         if retcode == 0:
00195           values.append(KeyValue(key = 'tx_heartbeat_errors', value = cmd_out))
00196         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_window_errors')
00197         if retcode == 0:
00198           values.append(KeyValue(key = 'tx_window_errors', value = cmd_out))
00199         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_dropped')
00200         if retcode == 0:
00201           values.append(KeyValue(key = 'tx_dropped', value = cmd_out))
00202         (retcode, cmd_out) = get_sys_net_stat(ifaces[i], 'tx_packets')
00203         if retcode == 0:
00204           values.append(KeyValue(key = 'tx_packets', value = cmd_out))
00205         #additional keys (https://www.kernel.org/doc/Documentation/ABI/testing/sysfs-class-net)
00206         (retcode, cmd_out) = get_sys_net(ifaces[i], 'addr_assign_type')
00207         if retcode == 0:
00208           try:
00209             tmp_dict = {'0': 'permanent address', '1': 'randomly generated', '2': 'stolen from another device', '3': 'set using dev_set_mac_address'}
00210             values.append(KeyValue(key = 'addr_assign_type', value = tmp_dict[cmd_out]))
00211           except KeyError, e:
00212             values.append(KeyValue(key = 'addr_assign_type', value = cmd_out))
00213         (retcode, cmd_out) = get_sys_net(ifaces[i], 'address')
00214         if retcode == 0:
00215           values.append(KeyValue(key = 'address', value = cmd_out))
00216         (retcode, cmd_out) = get_sys_net(ifaces[i], 'carrier')
00217         if retcode == 0:
00218           try:
00219             tmp_dict = {'0': 'physical link is down', '1': 'physical link is up'}
00220             values.append(KeyValue(key = 'carrier', value = tmp_dict[cmd_out]))
00221           except KeyError, e:
00222             values.append(KeyValue(key = 'carrier', value = cmd_out))
00223         (retcode, cmd_out) = get_sys_net(ifaces[i], 'carrier_changes')
00224         if retcode == 0:
00225           values.append(KeyValue(key = 'carrier_changes', value = cmd_out))
00226         (retcode, cmd_out) = get_sys_net(ifaces[i], 'carrier_up_count')
00227         if retcode == 0:
00228           values.append(KeyValue(key = 'carrier_up_count', value = cmd_out))
00229         (retcode, cmd_out) = get_sys_net(ifaces[i], 'carrier_down_count')
00230         if retcode == 0:
00231           values.append(KeyValue(key = 'carrier_down_count', value = cmd_out))
00232         (retcode, cmd_out) = get_sys_net(ifaces[i], 'speed')
00233         if retcode == 0:
00234           values.append(KeyValue(key = 'speed', value = cmd_out))
00235         (retcode, cmd_out) = get_sys_net(ifaces[i], 'tx_queue_len')
00236         if retcode == 0:
00237           values.append(KeyValue(key = 'tx_queue_len', value = cmd_out))
00238     except Exception, e:
00239       rospy.logerr(traceback.format_exc())
00240       msg = 'Network Usage Check Error'
00241       values.append(KeyValue(key = msg, value = str(e)))
00242       level = DiagnosticStatus.ERROR
00243     return level, net_dict[level], values
00244 
00245   def check_usage(self, event):
00246     diag_level = DiagnosticStatus.OK
00247     diag_vals = []
00248     diag_msgs = []
00249     net_level, net_msg, net_vals = self.check_network()
00250     diag_vals.extend(net_vals)
00251     if net_level > DiagnosticStatus.OK:
00252       diag_msgs.append(net_msg)
00253     diag_level = max(diag_level, net_level)
00254     if diag_msgs and diag_level > DiagnosticStatus.OK:
00255       usage_msg = ', '.join(set(diag_msgs))
00256     else:
00257       usage_msg = stat_dict[diag_level]
00258     with self._mutex:
00259       self._usage_stat.level = diag_level
00260       self._usage_stat.values = diag_vals
00261       self._usage_stat.message = usage_msg
00262 
00263   def publish_stats(self, event):
00264     with self._mutex:
00265       msg = DiagnosticArray()
00266       msg.header.stamp = rospy.get_rostime()
00267       msg.status.append(self._usage_stat)
00268       self._diag_pub.publish(msg)
00269 
00270 if __name__ == '__main__':
00271   net_node = NetMonitor()
00272   rospy.spin()


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Sun Jun 9 2019 20:20:19