power_wires.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, 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 #import roslib
00036 #roslib.load_manifest(PKG)
00037 
00038 import sys
00039 import rospy
00040 from diagnostic_msgs.msg import *
00041 
00042 
00043 def recurse_tree(element, messages, wiremap):
00044     errors = []
00045     print "Looking at ", element
00046     if element in wiremap:
00047         if "children" in wiremap[element]:
00048             for child in wiremap[element]["children"]:
00049                 errors_return = recurse_tree(child, messages, wiremap)
00050                 errors.extend(errors_return)
00051 
00052                 try:
00053                     value = float(messages[ wiremap[element]['component']][wiremap[element]['value']])
00054                     child_value = float(messages[ wiremap[child]['component']][wiremap[child]['value']])
00055                     tolerance = wiremap[element]['tolerance']
00056                     if abs(value - child_value) / value > tolerance/100.0:
00057                         errors.append("difference between %f (%s) and %f (%s) voltages exceeds tolerance %f percent"%(value, element, child_value, child, tolerance))
00058                     else:
00059                         rospy.logdebug("%s passed"%child)
00060                 except KeyError, e:
00061                     errors.append("badly formed parameters for element %s: %s"%(element, e));
00062         else:
00063             print "No children of element: ", element
00064     else:
00065         errors.append("no element %s"% element)
00066         #print "wiremap is", wiremap
00067     return errors
00068 
00069 
00070 def test(latest_status, parameters):
00071     #print latest_status
00072     results = {}
00073 
00074     if "wiring_tree" in parameters:
00075         wiremap = parameters["wiring_tree"]
00076     else:
00077         results['error'] = ["power_wires: no wiring_tree found"]
00078         return results
00079 
00080     if 'root' in parameters:
00081         results['error'] = []
00082         for root in parameters["root"]:
00083             results['error'].extend( recurse_tree(root, latest_status, wiremap))
00084         # clean up if no iterations happend
00085         if results['error'] == []:
00086             del results['error']
00087     else:
00088         results['error'] = ["power_wires: no root found"]
00089         return results
00090 
00091 
00092     return results
00093 
00094     


pr2_power_board
Author(s): Curt Meyers, Blaise Gassend
autogenerated on Tue Apr 22 2014 19:34:59