wifi_monitor.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 from __future__ import with_statement, print_function
00019 
00020 import threading
00021 import sys
00022 
00023 import rospy
00024 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00025 from cob_msgs.msg import AccessPoint
00026 
00027 DIAG_NAME = 'Wifi Status (ddwrt)'
00028 WARN_TIME = 30
00029 ERROR_TIME = 60
00030 
00031 
00032 def wifi_to_diag(msg):
00033     stat = DiagnosticStatus()
00034 
00035     stat.name = DIAG_NAME
00036     stat.level = DiagnosticStatus.OK
00037     stat.message = 'OK'
00038 
00039     stat.values.append(KeyValue(key='ESSID',       value=msg.essid))
00040     stat.values.append(KeyValue(key='Mac Address', value=msg.macaddr))
00041     stat.values.append(KeyValue(key='Signal',      value=str(msg.signal)))
00042     stat.values.append(KeyValue(key='Noise',       value=str(msg.noise)))
00043     stat.values.append(KeyValue(key='Sig/Noise',   value=str(msg.snr)))
00044     stat.values.append(KeyValue(key='Channel',     value=str(msg.channel)))
00045     stat.values.append(KeyValue(key='Rate',        value=msg.rate))
00046     stat.values.append(KeyValue(key='TX Power',    value=msg.tx_power))
00047     stat.values.append(KeyValue(key='Quality',     value=str(msg.quality)))
00048 
00049     return stat
00050 
00051 def mark_diag_stale(diag_stat = None, error = False):
00052     if not diag_stat:
00053         diag_stat = DiagnosticStatus()
00054         diag_stat.message = 'No Updates'
00055         diag_stat.name    = DIAG_NAME
00056     else:
00057         diag_stat.message = 'Updates Stale'
00058 
00059     diag_stat.level = DiagnosticStatus.WARN
00060     if error:
00061         diag_stat.level = DiagnosticStatus.ERROR
00062 
00063     return diag_stat
00064 
00065 class WifiMonitor(object):
00066     def __init__(self):
00067         self._mutex = threading.Lock()
00068 
00069         self._last_msg = None
00070         self._last_update_time = None
00071         self._start_time = rospy.get_time()
00072 
00073         self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=50)
00074 
00075         self._ddwrt_sub = rospy.Subscriber('ddwrt/accesspoint', AccessPoint, self._cb)
00076 
00077     def _cb(self, msg):
00078         with self._mutex:
00079             self._last_msg = msg
00080             self._last_update_time = rospy.get_time()
00081 
00082     def publish_stats(self):
00083         with self._mutex:
00084             if self._last_msg:
00085                 ddwrt_stat = wifi_to_diag(self._last_msg)
00086 
00087                 update_diff = rospy.get_time() - self._last_update_time
00088                 if update_diff > WARN_TIME:
00089                     ddwrt_stat = mark_diag_stale(ddwrt_stat)
00090                 if (rospy.get_time() - self._last_update_time) > ERROR_TIME:
00091                     ddwrt_stat = mark_diag_stale(ddwrt_stat, True)
00092 
00093                 ddwrt_stat.values.append(KeyValue(key='Time Since Update', value=str(update_diff)))
00094             else:
00095                 error_state = (rospy.get_time() - self._start_time) > ERROR_TIME
00096                 ddwrt_stat = mark_diag_stale(None, error_state)
00097                 ddwrt_stat.values.append(KeyValue(key='Time Since Update', value="N/A"))
00098 
00099         msg = DiagnosticArray()
00100         msg.header.stamp = rospy.get_rostime()
00101         msg.status.append(ddwrt_stat)
00102 
00103         self._diag_pub.publish(msg)
00104 
00105 
00106 if __name__ == '__main__':
00107     try:
00108         rospy.init_node('ddwrt_diag')
00109     except rospy.exceptions.ROSInitException:
00110         print('Wifi monitor is unable to initialize node. Master may not be running.', file=sys.stderr)
00111         sys.exit(2)
00112 
00113     wifi_monitor = WifiMonitor()
00114     rate = rospy.Rate(1.0)
00115 
00116     try:
00117         while not rospy.is_shutdown():
00118             rate.sleep()
00119             wifi_monitor.publish_stats()
00120     except KeyboardInterrupt:
00121         pass
00122     except Exception, e:
00123         import traceback
00124         traceback.print_exc()
00125 
00126     sys.exit(0)
00127 


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