pub_mech_stats.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2010, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of the Willow Garage nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 #
00035 
00036 ##\author Kevin Watts
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 


pr2_mechanism_diagnostics
Author(s): Kevin Watts
autogenerated on Wed Aug 26 2015 15:37:23