power_wires.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 #import roslib
36 #roslib.load_manifest(PKG)
37 
38 import sys
39 import rospy
40 from diagnostic_msgs.msg import *
41 
42 
43 def recurse_tree(element, messages, wiremap):
44  errors = []
45  print "Looking at ", element
46  if element in wiremap:
47  if "children" in wiremap[element]:
48  for child in wiremap[element]["children"]:
49  errors_return = recurse_tree(child, messages, wiremap)
50  errors.extend(errors_return)
51 
52  try:
53  value = float(messages[ wiremap[element]['component']][wiremap[element]['value']])
54  child_value = float(messages[ wiremap[child]['component']][wiremap[child]['value']])
55  tolerance = wiremap[element]['tolerance']
56  if abs(value - child_value) / value > tolerance/100.0:
57  errors.append("difference between %f (%s) and %f (%s) voltages exceeds tolerance %f percent"%(value, element, child_value, child, tolerance))
58  else:
59  rospy.logdebug("%s passed"%child)
60  except KeyError, e:
61  errors.append("badly formed parameters for element %s: %s"%(element, e));
62  else:
63  print "No children of element: ", element
64  else:
65  errors.append("no element %s"% element)
66  #print "wiremap is", wiremap
67  return errors
68 
69 
70 def test(latest_status, parameters):
71  #print latest_status
72  results = {}
73 
74  if "wiring_tree" in parameters:
75  wiremap = parameters["wiring_tree"]
76  else:
77  results['error'] = ["power_wires: no wiring_tree found"]
78  return results
79 
80  if 'root' in parameters:
81  results['error'] = []
82  for root in parameters["root"]:
83  results['error'].extend( recurse_tree(root, latest_status, wiremap))
84  # clean up if no iterations happend
85  if results['error'] == []:
86  del results['error']
87  else:
88  results['error'] = ["power_wires: no root found"]
89  return results
90 
91 
92  return results
93 
94 
def test(latest_status, parameters)
Definition: power_wires.py:70
def recurse_tree(element, messages, wiremap)
Definition: power_wires.py:43


pr2_power_board
Author(s): Curt Meyers, Blaise Gassend
autogenerated on Wed Jun 5 2019 20:40:40