38 PKG =
'pr2_mechanism_diagnostics' 39 import roslib; roslib.load_manifest(PKG)
42 from pr2_mechanism_msgs.msg
import MechanismStatistics, ControllerStatistics, JointStatistics
50 jnt_st = JointStatistics()
52 jnt_st.position = random.uniform(-1, 1)
54 jnt_st.position = float(
'NaN')
55 jnt_st.is_calibrated = calibrated
56 jnt_st.timestamp = rospy.get_rostime()
60 def ctrl_stat(name, running = True, overrun = False):
61 ctrl_st = ControllerStatistics()
63 ctrl_st.timestamp = rospy.get_rostime()
64 ctrl_st.running = running
66 ctrl_st.time_last_control_loop_overrun = rospy.get_rostime() - rospy.Duration(5)
67 ctrl_st.num_control_loop_overruns = 10
71 if __name__ ==
'__main__':
72 rospy.init_node(
'mech_stat_pub')
74 pub_cal = rospy.get_param(
"mech_diag/cal",
True)
75 pub_nan = rospy.get_param(
"mech_diag/nan",
False)
77 pub_running = rospy.get_param(
"mech_diag/running",
True)
78 pub_overrun = rospy.get_param(
"mech_diag/overrun",
False)
80 mech_st = MechanismStatistics()
81 mech_st.joint_statistics = [
joint_stat(
'my_joint', pub_cal, pub_nan) ]
82 mech_st.controller_statistics = [
ctrl_stat(
'my_controller', pub_running, pub_overrun) ]
84 pub_mech_stats = rospy.Publisher(
'mechanism_statistics', MechanismStatistics)
85 my_rate = rospy.Rate(RATE)
87 while not rospy.is_shutdown():
88 pub_mech_stats.publish(mech_st)
def ctrl_stat(name, running=True, overrun=False)
def joint_stat(name, calibrated=True, nan=False)