joints_to_diagnostics.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 # Copyright (c) 2009, Willow Garage, Inc.
00003 # All rights reserved.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 #
00008 #     * Redistributions of source code must retain the above copyright
00009 #       notice, this list of conditions and the following disclaimer.
00010 #     * Redistributions in binary form must reproduce the above copyright
00011 #       notice, this list of conditions and the following disclaimer in the
00012 #       documentation and/or other materials provided with the distribution.
00013 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00014 #       contributors may be used to endorse or promote products derived from
00015 #       this software without specific prior written permission.
00016 #
00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 # POSSIBILITY OF SUCH DAMAGE.
00028 
00029 from __future__ import with_statement
00030 
00031 import sys
00032 import rospy
00033 
00034 from pr2_mechanism_msgs.msg import MechanismStatistics
00035 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00036 
00037 import math
00038 
00039 import threading
00040 mutex = threading.Lock()
00041 
00042 has_warned_invalid = False
00043 
00044 # Math.isnan is new in python 2.6, need to check version
00045 
00046 check_nan = False
00047 my_version = sys.version_info
00048 if my_version[0] == 2 and my_version[1] >= 6:
00049     check_nan = True
00050 
00051 
00052 def joint_to_diag(js):
00053     global has_warned_invalid
00054     ds = DiagnosticStatus()
00055     ds.level = DiagnosticStatus.OK
00056     ds.message = 'OK'
00057 
00058     # Hack to stop gripper joints from being "uncalibrated"
00059     if not js.is_calibrated and js.name.find("float") < 0 and js.name.find("finger") < 0:
00060         ds.level = DiagnosticStatus.WARN
00061         ds.message = 'Uncalibrated'
00062 
00063     if check_nan and (math.isnan(js.position) or math.isnan(js.velocity) or
00064                       math.isnan(js.measured_effort) or math.isnan(js.commanded_effort)):
00065         ds.level = DiagnosticStatus.ERROR
00066         ds.message = 'NaN in joint data'
00067         if not has_warned_invalid:
00068             rospy.logerr(
00069                 "NaN value for joint data. controller_manager restart required.")
00070             has_warned_invalid = True
00071 
00072     if check_nan and (math.isinf(js.position) or math.isinf(js.velocity) or
00073                       math.isinf(js.measured_effort) or math.isinf(js.commanded_effort)):
00074         ds.level = DiagnosticStatus.ERROR
00075         ds.message = 'Inf in joint data'
00076         if not has_warned_invalid:
00077             rospy.logerr(
00078                 "Infinite value for joint data. controller_manager restart required.")
00079             has_warned_invalid = True
00080 
00081     ds.name = "Joint (%s)" % js.name
00082     ds.values = [
00083         KeyValue('Position', str(js.position)),
00084         KeyValue('Velocity', str(js.velocity)),
00085         KeyValue('Measured Effort', str(js.measured_effort)),
00086         KeyValue('Commanded Effort', str(js.commanded_effort)),
00087         KeyValue('Calibrated', str(js.is_calibrated)),
00088         KeyValue('Odometer', str(js.odometer)),
00089         KeyValue('Max Position', str(js.max_position)),
00090         KeyValue('Min Position', str(js.min_position)),
00091         KeyValue('Max Abs. Velocity', str(js.max_abs_velocity)),
00092         KeyValue('Max Abs. Effort', str(js.max_abs_effort)),
00093         KeyValue('Limits Hit', str(js.violated_limits))]
00094 
00095     return ds
00096 
00097 
00098 rospy.init_node('joints_to_diagnostics')
00099 
00100 last_msg = None
00101 last_update_time = 0
00102 
00103 
00104 def state_cb(msg):
00105     with mutex:
00106         global last_msg, last_update_time
00107         last_msg = msg
00108         last_update_time = rospy.get_time()
00109 
00110 
00111 def publish_diags():
00112     with mutex:
00113         global last_msg, last_update_time
00114         if last_msg is None:
00115             return
00116 
00117         # Don't publish anything without updates
00118         if rospy.get_time() - last_update_time > 3:
00119             return
00120 
00121         d = DiagnosticArray()
00122         d.header.stamp = last_msg.header.stamp
00123         if last_msg.joint_statistics == []:
00124             ds = DiagnosticStatus()
00125             ds.level = 0
00126             ds.message = 'No Joint states from controller manager'
00127             ds.name = "Joints: none"
00128             d.status = [ds]
00129         else:
00130             d.status = [joint_to_diag(js) for js in last_msg.joint_statistics]
00131         pub_diag.publish(d)
00132 
00133 pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
00134 rospy.Subscriber('mechanism_statistics', MechanismStatistics, state_cb)
00135 
00136 my_rate = rospy.Rate(1.0)
00137 while not rospy.is_shutdown():
00138     my_rate.sleep()
00139     publish_diags()


sr_edc_controller_configuration
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Mon Jul 1 2019 20:06:21