35 from __future__
import with_statement, division
37 import roslib; roslib.load_manifest(
'diagnostic_common_diagnostics')
39 import diagnostic_updater
as DIAG
46 from StringIO
import StringIO
85 lines.append(str(self.
name))
86 lines.append(
"\t" +
"Type: " + str(self.
type))
88 lines.append(
"\t" +
"Input: " + str(self.
input))
90 lines.append(
"\t" +
"Min: " + str(self.
min))
92 lines.append(
"\t" +
"Max: " + str(self.
max))
94 lines.append(
"\t" +
"High: " + str(self.
high))
96 lines.append(
"\t" +
"Crit: " + str(self.
critical))
97 lines.append(
"\t" +
"Alarm: " + str(self.
alarm))
98 return "\n".join(lines)
104 [name, reading] = line.split(
":")
107 if name.find(
"temp") != -1:
110 [sensor.name, sensor.type] = name.rsplit(
" ",1)
112 if sensor.name ==
"Core":
114 sensor.type =
"Temperature" 115 elif sensor.name.find(
"Physical id") != -1:
117 sensor.type =
"Temperature" 119 [reading, params] = reading.lstrip().split(
"(")
122 if line.find(
"ALARM") != -1:
125 if reading.find(
"\xc2\xb0C") == -1:
126 sensor.input = float(reading.split()[0])
128 sensor.input = float(reading.split(
"\xc2\xb0C")[0])
130 params = params.split(
",")
132 m = re.search(
"[0-9]+.[0-9]*", param)
133 if param.find(
"min") != -1:
134 sensor.min = float(m.group(0))
135 elif param.find(
"max") != -1:
136 sensor.max = float(m.group(0))
137 elif param.find(
"high") != -1:
138 sensor.high = float(m.group(0))
139 elif param.find(
"crit") != -1:
140 sensor.critical = float(m.group(0))
145 return rads / (2 * math.pi) * 60
148 return rpm * (2 * math.pi) / 60
151 out = StringIO(output)
154 for line
in out.readlines():
156 if line.find(
":") != -1
and line.find(
"Adapter") == -1:
163 p = subprocess.Popen(
'sensors', stdout = subprocess.PIPE,
164 stderr = subprocess.PIPE, shell =
True)
165 (o,e) = p.communicate()
166 if not p.returncode == 0:
176 rospy.loginfo(
"Ignore fanspeed warnings: %s" % self.
ignore_fans)
179 self.updater.setHardwareID(
"none")
185 self.updater.update()
189 stat.summary(DIAG.OK,
"OK")
191 if sensor.getType() ==
"Temperature":
192 if sensor.getInput() > sensor.getCrit():
193 stat.mergeSummary(DIAG.ERROR,
"Critical Temperature")
194 elif sensor.getInput() > sensor.getHigh():
195 stat.mergeSummary(DIAG.WARN,
"High Temperature")
196 stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
197 elif sensor.getType() ==
"Voltage":
198 if sensor.getInput() < sensor.getMin():
199 stat.mergeSummary(DIAG.ERROR,
"Low Voltage")
200 elif sensor.getInput() > sensor.getMax():
201 stat.mergeSummary(DIAG.ERROR,
"High Voltage")
202 stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
203 elif sensor.getType() ==
"Speed":
205 if sensor.getInput() < sensor.getMin():
206 stat.mergeSummary(DIAG.ERROR,
"No Fan Speed")
207 stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
210 rospy.logerr(
'Unable to process lm-sensors data')
211 rospy.logerr(traceback.format_exc())
214 if __name__ ==
'__main__':
215 hostname = socket.gethostname()
216 hostname_clean = string.translate(hostname, string.maketrans(
'-',
'_'))
218 rospy.init_node(
'sensors_monitor_%s'%hostname_clean)
219 except rospy.ROSInitException:
220 print >> sys.stderr,
'Unable to initialize node. Master may not be running'
def parse_sensors_output(output)
def parse_sensor_line(line)
def timer_cb(self, dummy)
def __init__(self, hostname)