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 from __future__ import with_statement, division
00036
00037 import roslib; roslib.load_manifest('diagnostic_common_diagnostics')
00038 import rospy
00039 import diagnostic_updater as DIAG
00040
00041 import socket, string
00042 import subprocess
00043 import math
00044 import re
00045 import sys
00046 from StringIO import StringIO
00047
00048 class Sensor(object):
00049 def __init__(self):
00050 self.critical = None
00051 self.min = None
00052 self.max = None
00053 self.input = None
00054 self.name = None
00055 self.type = None
00056 self.high = None
00057 self.alarm = None
00058
00059 def getCrit(self):
00060 return self.critical
00061
00062 def getMin(self):
00063 return self.min
00064
00065 def getMax(self):
00066 return self.max
00067
00068 def getInput(self):
00069 return self.input
00070
00071 def getName(self):
00072 return self.name
00073
00074 def getType(self):
00075 return self.type
00076
00077 def getHigh(self):
00078 return self.high
00079
00080 def getAlarm(self):
00081 return self.alarm
00082
00083 def __str__(self):
00084 lines = []
00085 lines.append(str(self.name))
00086 lines.append("\t" + "Type: " + str(self.type))
00087 if self.input:
00088 lines.append("\t" + "Input: " + str(self.input))
00089 if self.min:
00090 lines.append("\t" + "Min: " + str(self.min))
00091 if self.max:
00092 lines.append("\t" + "Max: " + str(self.max))
00093 if self.high:
00094 lines.append("\t" + "High: " + str(self.high))
00095 if self.critical:
00096 lines.append("\t" + "Crit: " + str(self.critical))
00097 lines.append("\t" + "Alarm: " + str(self.alarm))
00098 return "\n".join(lines)
00099
00100
00101 def parse_sensor_line(line):
00102 sensor = Sensor()
00103 line = line.lstrip()
00104 [name, reading] = line.split(":")
00105
00106
00107 if name.find("temp") != -1:
00108 return None
00109 else:
00110 [sensor.name, sensor.type] = name.rsplit(" ",1)
00111
00112 if sensor.name == "Core":
00113 sensor.name = name
00114 sensor.type = "Temperature"
00115 elif sensor.name.find("Physical id") != -1:
00116 sensor.name = name
00117 sensor.type = "Temperature"
00118
00119 [reading, params] = reading.lstrip().split("(")
00120
00121 sensor.alarm = False
00122 if line.find("ALARM") != -1:
00123 sensor.alarm = True
00124
00125 if reading.find("\xc2\xb0C") == -1:
00126 sensor.input = float(reading.split()[0])
00127 else:
00128 sensor.input = float(reading.split("\xc2\xb0C")[0])
00129
00130 params = params.split(",")
00131 for param in params:
00132 m = re.search("[0-9]+.[0-9]*", param)
00133 if param.find("min") != -1:
00134 sensor.min = float(m.group(0))
00135 elif param.find("max") != -1:
00136 sensor.max = float(m.group(0))
00137 elif param.find("high") != -1:
00138 sensor.high = float(m.group(0))
00139 elif param.find("crit") != -1:
00140 sensor.critical = float(m.group(0))
00141
00142 return sensor
00143
00144 def _rads_to_rpm(rads):
00145 return rads / (2 * math.pi) * 60
00146
00147 def _rpm_to_rads(rpm):
00148 return rpm * (2 * math.pi) / 60
00149
00150 def parse_sensors_output(output):
00151 out = StringIO(output)
00152
00153 sensorList = []
00154 for line in out.readlines():
00155
00156 if line.find(":") != -1 and line.find("Adapter") == -1:
00157 s = parse_sensor_line(line)
00158 if s is not None:
00159 sensorList.append(s)
00160 return sensorList
00161
00162 def get_sensors():
00163 p = subprocess.Popen('sensors', stdout = subprocess.PIPE,
00164 stderr = subprocess.PIPE, shell = True)
00165 (o,e) = p.communicate()
00166 if not p.returncode == 0:
00167 return ''
00168 if not o:
00169 return ''
00170 return o
00171
00172 class SensorsMonitor(object):
00173 def __init__(self, hostname):
00174 self.hostname = hostname
00175 self.ignore_fans = rospy.get_param('~ignore_fans', False)
00176 rospy.loginfo("Ignore fanspeed warnings: %s" % self.ignore_fans)
00177
00178 self.updater = DIAG.Updater()
00179 self.updater.setHardwareID("none")
00180 self.updater.add('%s Sensor Status'%self.hostname, self.monitor)
00181
00182 self.timer = rospy.Timer(rospy.Duration(1), self.timer_cb)
00183
00184 def timer_cb(self, dummy):
00185 self.updater.update()
00186
00187 def monitor(self, stat):
00188 try:
00189 stat.summary(DIAG.OK, "OK")
00190 for sensor in parse_sensors_output(get_sensors()):
00191 if sensor.getType() == "Temperature":
00192 if sensor.getInput() > sensor.getCrit():
00193 stat.mergeSummary(DIAG.ERROR, "Critical Temperature")
00194 elif sensor.getInput() > sensor.getHigh():
00195 stat.mergeSummary(DIAG.WARN, "High Temperature")
00196 stat.add(" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
00197 elif sensor.getType() == "Voltage":
00198 if sensor.getInput() < sensor.getMin():
00199 stat.mergeSummary(DIAG.ERROR, "Low Voltage")
00200 elif sensor.getInput() > sensor.getMax():
00201 stat.mergeSummary(DIAG.ERROR, "High Voltage")
00202 stat.add(" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
00203 elif sensor.getType() == "Speed":
00204 if not ignore_fans:
00205 if sensor.getInput() < sensor.getMin():
00206 stat.mergeSummary(DIAG.ERROR, "No Fan Speed")
00207 stat.add(" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
00208 except Exception, e:
00209 import traceback
00210 rospy.logerr('Unable to process lm-sensors data')
00211 rospy.logerr(traceback.format_exc())
00212 return stat
00213
00214 if __name__ == '__main__':
00215 hostname = socket.gethostname()
00216 hostname_clean = string.translate(hostname, string.maketrans('-','_'))
00217 try:
00218 rospy.init_node('sensors_monitor_%s'%hostname_clean)
00219 except rospy.ROSInitException:
00220 print >> sys.stderr, 'Unable to initialize node. Master may not be running'
00221 sys.exit(0)
00222
00223 monitor = SensorsMonitor(hostname)
00224 rospy.spin()