37 from __future__
import division
39 PKG =
'pr2_computer_monitor' 40 import roslib; roslib.load_manifest(PKG)
44 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus, KeyValue
45 from pr2_msgs.msg
import GPUStatus
53 return rads / (2 * math.pi) * 60
56 return rpm * (2 * math.pi) / 60
59 stat = DiagnosticStatus()
60 stat.name =
'GPU Status' 62 stat.level = DiagnosticStatus.OK
63 stat.hardware_id = gpu_stat.pci_device_id
65 stat.values.append(KeyValue(key=
'Product Name', value = gpu_stat.product_name))
66 stat.values.append(KeyValue(key=
'PCI Device/Vendor ID', value = gpu_stat.pci_device_id))
67 stat.values.append(KeyValue(key=
'PCI Location ID', value = gpu_stat.pci_location))
68 stat.values.append(KeyValue(key=
'Display', value = gpu_stat.display))
69 stat.values.append(KeyValue(key=
'Driver Version', value = gpu_stat.driver_version))
70 stat.values.append(KeyValue(key=
'Temperature (C)', value =
'%.0f' % gpu_stat.temperature))
71 stat.values.append(KeyValue(key=
'Fan Speed (RPM)', value =
'%.0f' %
_rads_to_rpm(gpu_stat.fan_speed)))
72 stat.values.append(KeyValue(key=
'Usage (%)', value =
'%.0f' % gpu_stat.gpu_usage))
73 stat.values.append(KeyValue(key=
'Memory (%)', value =
'%.0f' % gpu_stat.memory_usage))
76 if not gpu_stat.product_name
or not gpu_stat.pci_device_id:
77 stat.level = DiagnosticStatus.ERROR
78 stat.message =
'No Device Data' 82 if gpu_stat.gpu_usage > 98:
83 stat.level = max(stat.level, DiagnosticStatus.WARN)
84 stat.message =
'High Load' 87 if gpu_stat.temperature > 90:
88 stat.level = max(stat.level, DiagnosticStatus.WARN)
89 stat.message =
'High Temperature' 90 if gpu_stat.temperature > 95:
91 stat.level = max(stat.level, DiagnosticStatus.ERROR)
92 stat.message =
'Temperature Alarm' 95 if gpu_stat.fan_speed == 0:
96 stat.level = max(stat.level, DiagnosticStatus.ERROR)
97 stat.message =
'No Fan Speed' 105 lines = output.split(
'\n')
107 tple = line.split(
':')
108 if not len(tple) > 1:
111 name = tple[0].strip()
112 val =
':'.join(tple[1:]).strip()
114 if not name.lower() == word.lower():
122 gpu_stat = GPUStatus()
125 gpu_stat.product_name =
_find_val(output,
'Product Name')
126 gpu_stat.pci_device_id =
_find_val(output,
'PCI Device/Vendor ID')
127 gpu_stat.pci_location =
_find_val(output,
'PCI Location ID')
128 gpu_stat.display =
_find_val(output,
'Display')
129 gpu_stat.driver_version =
_find_val(output,
'Driver Version')
131 temp_str =
_find_val(output,
'Temperature')
133 temp, units = temp_str.split()
134 gpu_stat.temperature = int(temp)
139 fan_spd = float(fan_str.strip(
'\%').strip()) * 0.01 * MAX_FAN_RPM
145 usage = usage_str.strip(
'\%').strip()
146 gpu_stat.gpu_usage = int(usage)
150 mem = mem_str.strip(
'\%').strip()
151 gpu_stat.memory_usage = int(mem)
156 p = subprocess.Popen(
'sudo nvidia-smi -a', stdout = subprocess.PIPE,
157 stderr = subprocess.PIPE, shell =
True)
158 (o, e) = p.communicate()
160 if not p.returncode == 0:
def _find_val(output, word)
def parse_smi_output(output)
def gpu_status_to_diag(gpu_stat)