38 from __future__
import with_statement, division
40 PKG =
'pr2_computer_monitor' 41 import roslib; roslib.load_manifest(PKG)
45 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus
46 from pr2_msgs.msg
import GPUStatus
48 import pr2_computer_monitor
52 self.
_pub = rospy.Publisher(
'/diagnostics', DiagnosticArray, queue_size=10)
53 self.
_gpu_pub = rospy.Publisher(
'gpu_status', GPUStatus, queue_size=10)
56 gpu_stat = GPUStatus()
57 stat = DiagnosticStatus()
59 card_out = pr2_computer_monitor.get_gpu_status()
60 gpu_stat = pr2_computer_monitor.parse_smi_output(card_out)
61 stat = pr2_computer_monitor.gpu_status_to_diag(gpu_stat)
62 except Exception
as e:
64 rospy.logerr(
'Unable to process nVidia GPU data')
65 rospy.logerr(traceback.format_exc())
67 gpu_stat.header.stamp = rospy.get_rostime()
69 array = DiagnosticArray()
70 array.header.stamp = rospy.get_rostime()
72 array.status = [ stat ]
74 self._pub.publish(array)
75 self._gpu_pub.publish(gpu_stat)
77 if __name__ ==
'__main__':
78 rospy.init_node(
'nvidia_temp_monitor')
81 my_rate = rospy.Rate(1.0)
82 while not rospy.is_shutdown():