cb_qual_test.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2009, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 ##\author Kevin Watts
36 ##\brief Analyzes results from counterbalance test controller
37 
38 PKG = 'pr2_counterbalance_check'
39 import roslib
40 roslib.load_manifest(PKG)
41 
42 import os
43 import rospy
44 
45 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
46 from std_msgs.msg import Bool
47 from joint_qualification_controllers.msg import CounterbalanceTestData
48 
50 
51 
53  def __init__(self):
54  self._sent_results = False
55  self._motors_halted = True
56  self._data = None
57 
58  self.motors_topic = rospy.Subscriber('pr2_ethercat/motors_halted', Bool, self._motors_cb)
59  self.data_topic = rospy.Subscriber('cb_test_data', CounterbalanceTestData, self._data_callback)
60  self._result_service = rospy.ServiceProxy('test_result', TestResult)
61 
62  self._model_file = rospy.get_param('~model_file', None)
63 
64 
65  def has_data(self):
66  return self._data is not None
67 
68  def send_results(self, r):
69  if not self._sent_results:
70  try:
71  rospy.wait_for_service('test_result', 10)
72  except:
73  rospy.logerr('Wait for service \'test_result\' timed out! Unable to send results.')
74  return False
75 
76  self._result_service.call(r)
77  self._sent_results = True
78 
79  return True
80 
81  def test_failed_service_call(self, except_str = ''):
82  rospy.logerr(except_str)
83  r = TestResultRequest()
84  r.html_result = except_str
85  r.text_summary = 'Caught exception, automated test failure.'
86  r.result = TestResultRequest.RESULT_FAIL
87  self.send_results(r)
88 
89  def _motors_cb(self, msg):
90  self._motors_halted = msg.data
91 
92  def _data_callback(self, msg):
93  self._data = msg
94 
95  def process_results(self):
96  msg = self._data
97  try:
98  data = CounterbalanceAnalysisData(msg)
99  params = CounterbalanceAnalysisParams(msg)
100 
101  lift_effort_result = analyze_lift_efforts(params, data)
102  lift_effort_plot = plot_efforts_by_lift_position(params, data)
103 
104  if params.flex_test:
105  flex_effort_result = analyze_flex_efforts(params, data)
106  lift_effort_contour = plot_effort_contour(params, data)
107  flex_effort_contour = plot_effort_contour(params, data, False)
108 
109  if self._model_file and os.path.exists(self._model_file):
110  adjust_result = check_cb_adjustment(params, data, self._model_file)
111  elif self._model_file:
112  adjust_result = CounterbalanceAnalysisResult()
113  adjust_result.result = False
114  adjust_result.html = '<p>CB model file is missing. File %s does not exist. This file is used for testing the CB adjustment.</p>\n' % self._model_file
115  adjust_result.summary = 'CB model file missing, unable to analyze'
116  else: # Don't check CB adjustment
117  adjust_result = CounterbalanceAnalysisResult()
118  adjust_result.result = True
119  adjust_result.html = '<p>Did not check counterbalance adjustment.</p>'
120 
121 
122  html = []
123  if params.flex_test:
124  if self._model_file:
125  html.append('<H4>CB Adjustment Recommendations and Analysis</H4>')
126  html.append(adjust_result.html)
127  html.append('<p>Further information is for debugging and analysis information only.</p><br><hr size="2" />')
128 
129  html.append('<H4>Lift Effort Contour Plot</H4>')
130  html.append('<img src=\"IMG_PATH/%s.png\" width=\"640\" height=\"480\" />' % (lift_effort_contour.title))
131  html.append('<H4>Flex Effort Contour Plot</H4>')
132  html.append('<img src=\"IMG_PATH/%s.png\" width=\"640\" height=\"480\" />' % (flex_effort_contour.title))
133 
134  html.append('<H4>Flex Effort Analysis</H4>')
135  html.append(flex_effort_result.html)
136 
137  html.append('<H4>Lift Effort Analysis</H4>')
138  html.append(lift_effort_result.html)
139  html.append('<img src=\"IMG_PATH/%s.png\" width=\"640\" height=\"480\" />' % (lift_effort_plot.title))
140 
141  html.append('<p>Test Parameters</p>')
142  html.append('<table border="1" cellpadding="2" cellspacing="0">')
143  html.append('<tr><td><b>Joint</b></td><td><b>Dither Amplitude</b></td></tr>')
144  html.append('<tr><td>%s</td><td>%s</td></tr>' % (params.lift_joint, params.lift_dither))
145  if params.flex_test:
146  html.append('<tr><td>%s</td><td>%s</td></tr>' % (params.flex_joint, params.flex_dither))
147  html.append('</table>')
148  html.append('<hr size=2>')
149 
150  r = TestResultRequest()
151  r.html_result = '\n'.join(html)
152  r.text_summary = ' '.join([lift_effort_result.summary])
153  if params.flex_test:
154  r.text_summary = ' '.join([r.text_summary, flex_effort_result.summary])
155 
156  r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
157 
158 
159  if params.flex_test and (lift_effort_result.result and
160  flex_effort_result.result and
161  adjust_result.result):
162  r.result = TestResultRequest.RESULT_PASS
163  elif not params.flex_test and lift_effort_result.result:
164  r.result = TestResultRequest.RESULT_PASS
165 
166 
167  r.plots = [ lift_effort_plot ]
168  if params.flex_test:
169  r.plots.append(lift_effort_contour)
170  r.plots.append(flex_effort_contour)
171  r.params = params.get_test_params()
172  r.values = lift_effort_result.values
173  if params.flex_test:
174  r.values.extend(flex_effort_result.values)
175  r.values.extend(adjust_result.values)
176 
177  # Adjustment required
178  if params.flex_test and not adjust_result.result:
179  r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
180  r.text_summary = adjust_result.summary
181 
182  # Check motors halted
183  if self._motors_halted:
184  r.text_summary = 'Fail, motors halted. Check estop and power board.'
185  r.html_result = '<H4>Motors Halted</H4>\n<p>Unable to analyze CB. Check estop and power board.</p>\n' + r.html_result
186  r.result = TestResultRequest.RESULT_FAIL
187 
188  # Check timeout of controller
189  if params.timeout_hit:
190  r.text_summary = 'Fail, controller timeout hit. Timeout = %.ds. Test terminated early.' % (int(params.named_params["Timeout"]))
191  r.html_result = '<H4>Timeout Hit</H4>\n<p>Unable to analyzer CB. Controller timeout hit.</p>\n' + r.html_result
192  r.result = TestResultRequest.RESULT_FAIL
193 
194 
195  self.send_results(r)
196  except Exception, e:
197  import traceback
198  self.test_failed_service_call(traceback.format_exc());
199 
200 
201 if __name__ == '__main__':
202  rospy.init_node('cb_analyzer')
204  try:
205  my_rate = rospy.Rate(5)
206  while not app.has_data() and not rospy.is_shutdown():
207  my_rate.sleep()
208 
209  if not rospy.is_shutdown():
210  app.process_results()
211 
212  rospy.spin()
213  except KeyboardInterrupt, e:
214  pass
215  except Exception, e:
216  print 'Caught Exception in CB application'
217  import traceback
218  traceback.print_exc()
219  result_service = rospy.ServiceProxy('test_result', TestResult)
220 
221  r = TestResultRequest()
222  r.html_result = traceback.format_exc()
223  r.text_summary = 'Caught exception, automated test failure.'
224  r.plots = []
225  r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
226  result_service.call(r)
def test_failed_service_call(self, except_str='')
Definition: cb_qual_test.py:81
def analyze_lift_efforts(params, data)
Checks shoulder lift efforts against params.
def plot_efforts_by_lift_position(params, data, flex_index=-1, lift_calc=True)
Plots CB efforts against shoulder lift position.
def check_cb_adjustment(params, data, model_file)
Return CB adjustments to minimize total torque.
def plot_effort_contour(params, data, lift_calc=True)
Gives effort contour plot of efforts by lift, flex position.
def analyze_flex_efforts(params, data)
Checks shoulder flex efforts against params.


pr2_counterbalance_check
Author(s): Kevin Watts
autogenerated on Wed Jan 6 2021 03:39:25