pub_mech_stats.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2010, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 
36 ##\author Kevin Watts
37 
38 PKG = 'pr2_mechanism_diagnostics'
39 import roslib; roslib.load_manifest(PKG)
40 
41 import rospy
42 from pr2_mechanism_msgs.msg import MechanismStatistics, ControllerStatistics, JointStatistics
43 
44 import random
45 
46 
47 RATE = 1.0
48 
49 def joint_stat(name, calibrated = True, nan = False):
50  jnt_st = JointStatistics()
51  jnt_st.name = name
52  jnt_st.position = random.uniform(-1, 1)
53  if nan:
54  jnt_st.position = float('NaN')
55  jnt_st.is_calibrated = calibrated
56  jnt_st.timestamp = rospy.get_rostime()
57 
58  return jnt_st
59 
60 def ctrl_stat(name, running = True, overrun = False):
61  ctrl_st = ControllerStatistics()
62  ctrl_st.name = name
63  ctrl_st.timestamp = rospy.get_rostime()
64  ctrl_st.running = running
65  if overrun:
66  ctrl_st.time_last_control_loop_overrun = rospy.get_rostime() - rospy.Duration(5)
67  ctrl_st.num_control_loop_overruns = 10
68 
69  return ctrl_st
70 
71 if __name__ == '__main__':
72  rospy.init_node('mech_stat_pub')
73 
74  pub_cal = rospy.get_param("mech_diag/cal", True)
75  pub_nan = rospy.get_param("mech_diag/nan", False)
76 
77  pub_running = rospy.get_param("mech_diag/running", True)
78  pub_overrun = rospy.get_param("mech_diag/overrun", False)
79 
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) ]
83 
84  pub_mech_stats = rospy.Publisher('mechanism_statistics', MechanismStatistics)
85  my_rate = rospy.Rate(RATE)
86 
87  while not rospy.is_shutdown():
88  pub_mech_stats.publish(mech_st)
89  my_rate.sleep()
90 
91 
def ctrl_stat(name, running=True, overrun=False)
def joint_stat(name, calibrated=True, nan=False)


pr2_mechanism_diagnostics
Author(s): Kevin Watts
autogenerated on Fri Jun 7 2019 22:04:25