Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 from __future__ import with_statement
00039
00040 PKG = 'pr2_computer_monitor'
00041 import roslib
00042 roslib.load_manifest(PKG)
00043
00044 import rospy
00045
00046 import threading
00047 import sys
00048
00049 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00050 from pr2_msgs.msg import AccessPoint
00051
00052 DIAG_NAME = 'Wifi Status (ddwrt)'
00053 WARN_TIME = 30
00054 ERROR_TIME = 60
00055
00056
00057 def wifi_to_diag(msg):
00058 stat = DiagnosticStatus()
00059
00060 stat.name = DIAG_NAME
00061 stat.level = DiagnosticStatus.OK
00062 stat.message = 'OK'
00063
00064 stat.values.append(KeyValue(key='ESSID', value=msg.essid))
00065 stat.values.append(KeyValue(key='Mac Address', value=msg.macaddr))
00066 stat.values.append(KeyValue(key='Signal', value=str(msg.signal)))
00067 stat.values.append(KeyValue(key='Noise', value=str(msg.noise)))
00068 stat.values.append(KeyValue(key='Sig/Noise', value=str(msg.snr)))
00069 stat.values.append(KeyValue(key='Channel', value=str(msg.channel)))
00070 stat.values.append(KeyValue(key='Rate', value=msg.rate))
00071 stat.values.append(KeyValue(key='TX Power', value=msg.tx_power))
00072 stat.values.append(KeyValue(key='Quality', value=str(msg.quality)))
00073
00074 return stat
00075
00076 def mark_diag_stale(diag_stat = None, error = False):
00077 if not diag_stat:
00078 diag_stat = DiagnosticStatus()
00079 diag_stat.message = 'No Updates'
00080 diag_stat.name = DIAG_NAME
00081 else:
00082 diag_stat.message = 'Updates Stale'
00083
00084 diag_stat.level = DiagnosticStatus.WARN
00085 if error:
00086 diag_stat.level = DiagnosticStatus.ERROR
00087
00088 return diag_stat
00089
00090 class WifiMonitor(object):
00091 def __init__(self):
00092 self._mutex = threading.Lock()
00093
00094 self._last_msg = None
00095 self._last_update_time = None
00096 self._start_time = rospy.get_time()
00097
00098 self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray)
00099
00100 self._ddwrt_sub = rospy.Subscriber('ddwrt/accesspoint', AccessPoint, self._cb)
00101
00102 def _cb(self, msg):
00103 with self._mutex:
00104 self._last_msg = msg
00105 self._last_update_time = rospy.get_time()
00106
00107 def publish_stats(self):
00108 with self._mutex:
00109 if self._last_msg:
00110 ddwrt_stat = wifi_to_diag(self._last_msg)
00111
00112 update_diff = rospy.get_time() - self._last_update_time
00113 if update_diff > WARN_TIME:
00114 ddwrt_stat = mark_diag_stale(ddwrt_stat)
00115 if (rospy.get_time() - self._last_update_time) > ERROR_TIME:
00116 ddwrt_stat = mark_diag_stale(ddwrt_stat, True)
00117
00118 ddwrt_stat.values.append(KeyValue(key='Time Since Update', value=str(update_diff)))
00119 else:
00120 error_state = (rospy.get_time() - self._start_time) > ERROR_TIME
00121 ddwrt_stat = mark_diag_stale(None, error_state)
00122 ddwrt_stat.values.append(KeyValue(key='Time Since Update', value="N/A"))
00123
00124 msg = DiagnosticArray()
00125 msg.header.stamp = rospy.get_rostime()
00126 msg.status.append(ddwrt_stat)
00127
00128 self._diag_pub.publish(msg)
00129
00130
00131 if __name__ == '__main__':
00132 try:
00133 rospy.init_node('ddwrt_diag')
00134 except rospy.exceptions.ROSInitException:
00135 print 'Wifi monitor is unable to initialize node. Master may not be running.'
00136 sys.exit(2)
00137
00138 wifi_monitor = WifiMonitor()
00139 rate = rospy.Rate(1.0)
00140
00141 try:
00142 while not rospy.is_shutdown():
00143 rate.sleep()
00144 wifi_monitor.publish_stats()
00145 except KeyboardInterrupt:
00146 pass
00147 except Exception, e:
00148 import traceback
00149 traceback.print_exc()
00150
00151 sys.exit(0)
00152
00153
00154