35 from __future__ 
import with_statement, division
 
   39 import diagnostic_updater 
as DIAG
 
   46 from io 
import StringIO
 
   47 roslib.load_manifest(
'diagnostic_common_diagnostics')
 
   62         return 'Sensor object (name: {}, type: {})'.format(self.
name,
 
   91         lines.append(str(self.
name))
 
   92         lines.append(
"\t" + 
"Type:  " + str(self.
type))
 
   94             lines.append(
"\t" + 
"Input: " + str(self.
input))
 
   96             lines.append(
"\t" + 
"Min:   " + str(self.
min))
 
   98             lines.append(
"\t" + 
"Max:   " + str(self.
max))
 
  100             lines.append(
"\t" + 
"High:  " + str(self.
high))
 
  102             lines.append(
"\t" + 
"Crit:  " + str(self.
critical))
 
  103         lines.append(
"\t" + 
"Alarm: " + str(self.
alarm))
 
  104         return "\n".join(lines)
 
  110     [name, reading] = line.split(
":")
 
  113         [sensor.name, sensor.type] = name.rsplit(
" ", 1)
 
  117     if sensor.name == 
"Core":
 
  119         sensor.type = 
"Temperature" 
  120     elif sensor.name.find(
"Physical id") != -1:
 
  122         sensor.type = 
"Temperature" 
  125         [reading, params] = reading.lstrip().split(
"(")
 
  130     if line.find(
"ALARM") != -1:
 
  133     if reading.find(
"°C") == -1:
 
  134         sensor.input = float(reading.split()[0])
 
  136         sensor.input = float(reading.split(
"°C")[0])
 
  138     params = params.split(
",")
 
  140         m = re.search(
"[0-9]+.[0-9]*", param)
 
  141         if param.find(
"min") != -1:
 
  142             sensor.min = float(m.group(0))
 
  143         elif param.find(
"max") != -1:
 
  144             sensor.max = float(m.group(0))
 
  145         elif param.find(
"high") != -1:
 
  146             sensor.high = float(m.group(0))
 
  147         elif param.find(
"crit") != -1:
 
  148             sensor.critical = float(m.group(0))
 
  154     return rads / (2 * math.pi) * 60
 
  158     return rpm * (2 * math.pi) / 60
 
  162     out = StringIO(output 
if isinstance(output, str) 
else output.decode(
'utf-8'))
 
  165     for line 
in out.readlines():
 
  167         if ":" in line 
and "Adapter" not in line:
 
  170             except Exception 
as exc:
 
  171                 rospy.logwarn(
'Unable to parse line "%s", due to %s', line, exc)
 
  178     p = subprocess.Popen(
'sensors', stdout=subprocess.PIPE,
 
  179                          stderr=subprocess.PIPE, shell=
True)
 
  180     (o, e) = p.communicate()
 
  181     if not p.returncode == 0:
 
  193         rospy.loginfo(
"Ignore fanspeed warnings: %s" % self.
ignore_fans)
 
  196         self.
updater.setHardwareID(
"none")
 
  206             stat.summary(DIAG.OK, 
"OK")
 
  208                 if sensor.getType() == 
"Temperature":
 
  209                     if sensor.getInput() > sensor.getCrit():
 
  210                         stat.mergeSummary(DIAG.ERROR, 
"Critical Temperature")
 
  211                     elif sensor.getInput() > sensor.getHigh():
 
  212                         stat.mergeSummary(DIAG.WARN, 
"High Temperature")
 
  213                     stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
 
  214                 elif sensor.getType() == 
"Voltage":
 
  215                     if sensor.getInput() < sensor.getMin():
 
  216                         stat.mergeSummary(DIAG.ERROR, 
"Low Voltage")
 
  217                     elif sensor.getInput() > sensor.getMax():
 
  218                         stat.mergeSummary(DIAG.ERROR, 
"High Voltage")
 
  219                     stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
 
  220                 elif sensor.getType() == 
"Speed":
 
  222                         if sensor.getInput() < sensor.getMin():
 
  223                             stat.mergeSummary(DIAG.ERROR, 
"No Fan Speed")
 
  224                     stat.add(
" ".join([sensor.getName(), sensor.getType()]), sensor.getInput())
 
  227             rospy.logerr(
'Unable to process lm-sensors data')
 
  228             rospy.logerr(traceback.format_exc())
 
  232 if __name__ == 
'__main__':
 
  233     hostname = socket.gethostname()
 
  234     hostname_clean = hostname.translate(hostname.maketrans(
'-', 
'_'))
 
  236         rospy.init_node(
'sensors_monitor_%s' % hostname_clean)
 
  237     except rospy.ROSInitException:
 
  238         print(
'Unable to initialize node. Master may not be running')