$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2009, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 ##\author Kevin Watts 00036 00037 ##\brief Publishes diagnostic messages for robot monitor regression test 00038 00039 PKG = 'runtime_monitor' 00040 00041 import roslib; roslib.load_manifest(PKG) 00042 00043 import rospy 00044 from time import sleep 00045 00046 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus 00047 00048 if __name__ == '__main__': 00049 rospy.init_node('diag_pub') 00050 pub = rospy.Publisher('/diagnostics', DiagnosticArray) 00051 00052 start_time = rospy.get_time() 00053 00054 while not rospy.is_shutdown(): 00055 array = DiagnosticArray() 00056 array.status = [ 00057 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_l_wheel_motor)', 'OK', '', []), 00058 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_r_wheel_motor)', 'OK', '', []), 00059 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_rotation_motor)', 'OK', '', []), 00060 DiagnosticStatus(2, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'Motor model', '', []), 00061 DiagnosticStatus(1, 'EtherCAT Device (fr_caster_r_wheel_motor)', 'High temperature', '', []), 00062 DiagnosticStatus(0, 'EtherCAT Device (fr_caster_rotation_motor)', 'OK', '', []), 00063 00064 DiagnosticStatus(0, 'tilt_hokuyo_node: Frequency Status', 'OK', '', []), 00065 DiagnosticStatus(0, 'tilt_hokuyo_node: Connection Status', 'OK', '', []), 00066 DiagnosticStatus(0, 'base_hokuyo_node: Frequency Status', 'OK', '', []), 00067 DiagnosticStatus(0, 'base_hokuyo_node: Connection Status', 'OK', '', []), 00068 00069 DiagnosticStatus(0, 'Joint (fl_caster_l_wheel_joint)', 'OK', '', []), 00070 DiagnosticStatus(0, 'Joint (fl_caster_r_wheel_joint)', 'OK', '', []), 00071 DiagnosticStatus(1, 'Joint (fl_caster_rotation_joint)', 'Uncalibrated', '', []), 00072 DiagnosticStatus(1, 'Joint (fr_caster_l_wheel_joint)', 'Uncalibrated', '', []), 00073 DiagnosticStatus(0, 'Joint (fr_caster_r_wheel_joint)', 'OK', '', []), 00074 DiagnosticStatus(0, 'Joint (fr_caster_rotation_joint)', 'OK', '', [])] 00075 array.header.stamp = rospy.get_rostime() 00076 00077 # Test that runtime monitor can handle an item changing levels 00078 if rospy.get_time() - start_time > 5: 00079 array.status.append(DiagnosticStatus(2, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'Motor model', '', [])) 00080 else: 00081 array.status.append(DiagnosticStatus(0, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'OK', '', [])) 00082 00083 pub.publish(array) 00084 sleep(1)