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
00030
00031
00032
00033
00034
00035
00036
00037
00038 PKG = 'pr2_mechanism_diagnostics'
00039 import roslib; roslib.load_manifest(PKG)
00040
00041 import rospy
00042 from pr2_mechanism_msgs.msg import MechanismStatistics, ControllerStatistics, JointStatistics
00043
00044 import random
00045
00046
00047 RATE = 1.0
00048
00049 def joint_stat(name, calibrated = True, nan = False):
00050 jnt_st = JointStatistics()
00051 jnt_st.name = name
00052 jnt_st.position = random.uniform(-1, 1)
00053 if nan:
00054 jnt_st.position = float('NaN')
00055 jnt_st.is_calibrated = calibrated
00056 jnt_st.timestamp = rospy.get_rostime()
00057
00058 return jnt_st
00059
00060 def ctrl_stat(name, running = True, overrun = False):
00061 ctrl_st = ControllerStatistics()
00062 ctrl_st.name = name
00063 ctrl_st.timestamp = rospy.get_rostime()
00064 ctrl_st.running = running
00065 if overrun:
00066 ctrl_st.time_last_control_loop_overrun = rospy.get_rostime() - rospy.Duration(5)
00067 ctrl_st.num_control_loop_overruns = 10
00068
00069 return ctrl_st
00070
00071 if __name__ == '__main__':
00072 rospy.init_node('mech_stat_pub')
00073
00074 pub_cal = rospy.get_param("mech_diag/cal", True)
00075 pub_nan = rospy.get_param("mech_diag/nan", False)
00076
00077 pub_running = rospy.get_param("mech_diag/running", True)
00078 pub_overrun = rospy.get_param("mech_diag/overrun", False)
00079
00080 mech_st = MechanismStatistics()
00081 mech_st.joint_statistics = [ joint_stat('my_joint', pub_cal, pub_nan) ]
00082 mech_st.controller_statistics = [ ctrl_stat('my_controller', pub_running, pub_overrun) ]
00083
00084 pub_mech_stats = rospy.Publisher('mechanism_statistics', MechanismStatistics)
00085 my_rate = rospy.Rate(RATE)
00086
00087 while not rospy.is_shutdown():
00088 pub_mech_stats.publish(mech_st)
00089 my_rate.sleep()
00090
00091