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 import roslib; roslib.load_manifest('pr2_controller_manager')
00030 import rospy
00031 
00032 from pr2_mechanism_msgs.msg import MechanismStatistics
00033 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00034 
00035 def controller_to_diag(c):
00036     d = DiagnosticStatus()
00037     d.name = 'Controller ('+c.name+')'
00038 
00039     d.level = 0
00040     if (c.running):
00041         d.message = 'Running'
00042     else:
00043         d.message = 'Stopped'
00044 
00045     if (not use_sim_time and c.num_control_loop_overruns > 0):
00046         d.message += ' !!! Broke Realtime, used '+str(int(c.max_time.to_sec()*1e6))+' micro seconds in update loop'
00047         if c.time_last_control_loop_overrun + rospy.Duration(30.0) > rospy.Time.now():
00048             d.level = 1
00049 
00050     d.values.append(KeyValue('Avg Time in Update Loop (usec)',str(int(c.mean_time.to_sec()*1e6))))
00051     d.values.append(KeyValue('Max Time in update Loop (usec)',str(int(c.max_time.to_sec()*1e6))))
00052     d.values.append(KeyValue('Variance on Time in Update Loop',str(int(c.variance_time.to_sec()*1e6))))
00053     d.values.append(KeyValue('Percent of Cycle Time Used',str(int(c.mean_time.to_sec()/0.00001))))
00054     d.values.append(KeyValue('Number of Control Loop Overruns',str(int(c.num_control_loop_overruns))))
00055     d.values.append(KeyValue('Timestamp of Last Control Loop Overrun (sec)',str(int(c.time_last_control_loop_overrun.to_sec()))))
00056     return d
00057 
00058 rospy.init_node('controller_to_diagnostics')
00059 use_sim_time = rospy.get_param('use_sim_time', False)
00060 pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
00061 
00062 last_publish_time = rospy.Time(0.0)
00063 def state_cb(msg):
00064     global last_publish_time
00065     now = rospy.get_rostime()
00066     if (now - last_publish_time).to_sec() > 1.0:
00067         if len(msg.controller_statistics) == 0:
00068             d = DiagnosticArray()
00069             d.header.stamp = msg.header.stamp
00070             ds = DiagnosticStatus()
00071             ds.name = "Controller: No controllers loaded in controller manager"
00072             d.status = [ds]
00073             pub_diag.publish(d)
00074         else:
00075             for c in msg.controller_statistics:
00076                 d = DiagnosticArray()
00077                 d.header.stamp = msg.header.stamp
00078                 d.status = [controller_to_diag(c)]
00079                 pub_diag.publish(d)
00080         last_publish_time = now
00081 
00082 rospy.Subscriber('mechanism_statistics', MechanismStatistics, state_cb)
00083 rospy.spin()