00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 PKG = "qualification"
00033 import roslib; roslib.load_manifest(PKG)
00034
00035 import numpy
00036
00037 import rospy
00038
00039 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
00040 from qualification.analysis.hysteresis_analysis import *
00041
00042 from joint_qualification_controllers.msg import HysteresisData
00043 from std_msgs.msg import Bool
00044
00045 import traceback
00046
00047 class AnalysisApp:
00048 def __init__(self):
00049 self.data_sent = False
00050 self._motors_halted = True
00051 rospy.init_node("test_plotter")
00052 self.data_topic = rospy.Subscriber("/test_data", HysteresisData, self._on_data)
00053 self.motors_topic = rospy.Subscriber("pr2_etherCAT/motors_halted", Bool, self.on_motor_cb)
00054 self.result_service = rospy.ServiceProxy('/test_result', TestResult)
00055 self.data = None
00056
00057 def _on_data(self, msg):
00058 self.data = msg
00059
00060 def has_data(self):
00061 return self.data is not None
00062
00063 def on_motor_cb(self, msg):
00064 self._motors_halted = msg.data
00065
00066 def test_failed_service_call(self, except_str = ''):
00067 rospy.logerr(except_str)
00068 r = TestResultRequest()
00069 r.html_result = except_str
00070 r.text_summary = 'Caught exception, automated test failure.'
00071 r.plots = []
00072 r.result = TestResultRequest.RESULT_FAIL
00073 self.send_results(r)
00074
00075 def send_results(self, test_result):
00076 if not self.data_sent:
00077 rospy.wait_for_service('test_result')
00078 self.result_service.call(test_result)
00079 self.data_sent = True
00080
00081 def hysteresis_plot(self):
00082 try:
00083 r = TestResultRequest()
00084 r.html_result = ''
00085 r.text_summary = 'No data.'
00086 r.plots = []
00087 r.result = TestResultRequest.RESULT_FAIL
00088
00089 image_title = self.data.joint_name + "_hysteresis"
00090
00091 params = HysteresisParameters()
00092 params.joint_name = self.data.joint_name
00093 params.pos_effort = self.data.arg_value[1]
00094 params.neg_effort = self.data.arg_value[0]
00095 params.range_max = self.data.arg_value[3]
00096 params.range_min = self.data.arg_value[2]
00097 params.tolerance = self.data.arg_value[7]
00098 params.sd_max = self.data.arg_value[8]
00099 params.slope = self.data.arg_value[9]
00100 params.timeout = self.data.arg_value[5]
00101 params.velocity = self.data.arg_value[4]
00102 params.max_effort = self.data.arg_value[6]
00103
00104 params.p_gain = self.data.arg_value[10]
00105 params.i_gain = self.data.arg_value[11]
00106 params.d_gain = self.data.arg_value[12]
00107 params.i_clamp = self.data.arg_value[13]
00108
00109 r.params = params.get_test_params()
00110
00111 if self._motors_halted:
00112 r.result = TestResultRequest.RESULT_FAIL
00113 r.text_summary = "Motors halted. Check runstop. Hysteresis results are invalid."
00114 r.html_result = "<p>Motors halted during test. Check estop and verify that power is on.</p>\n"
00115 self.send_results(r)
00116
00117
00118 if len(self.data.position_up) < 20 or len(self.data.position_down) < 20:
00119 r.result = TestResultRequest.RESULT_FAIL
00120 r.text_summary = "Not enough data points, bad encoder or bad gains."
00121
00122 error_msg = "<p>Not enough data points, hysteresis controller may have malfunctioned. Check diagnostics.</p>"
00123 error_msg += "<p>Up data points: %d, down points: %d</p>\n" % (len(self.data.position_up), len(self.data.position_down))
00124 error_msg += "<p>The encoder may be missing ticks, check encoder.<br>\n"
00125 error_msg += "Make sure mechanism is free to move and not trapped or constrained<br>\n"
00126 error_msg += "Make sure motors are not in safety lockout (check diagnostics)<br>\n"
00127 error_msg += "Check controller gains if problem persists on components of same type.</p>\n"
00128 error_msg += "<p>Test status: <b>FAIL</b>.</p>"
00129 error_msg += '<p align=center><b>Test Parameters</b></p>\n'
00130
00131 r.html_result = error_msg
00132 self.send_results(r)
00133 return
00134
00135 if self.data.arg_value[5] == 0:
00136 r.result = TestResultRequest.RESULT_FAIL
00137 r.text_summary = 'Hysteresis controller timed out. Check diagnostics.'
00138 r.html_result = '<p>Hysteresis controller timed out. Check diagnostics. Controller gains may be bad, or motors may be in safety lockout. Did the device pass the visualizer? Is it calibrated?</p><p>Test status: <b>FAIL</b>.</p>'
00139 r.html_result += '<p align=center><b>Test Parameters</b></p>\n'
00140 self.send_results(r)
00141 return
00142
00143
00144 min_encoder = min(min(numpy.array(self.data.position_up)), min(numpy.array(self.data.position_down)))
00145 max_encoder = max(max(numpy.array(self.data.position_up)), max(numpy.array(self.data.position_down)))
00146
00147 if abs(max_encoder - min_encoder) < 0.005:
00148 r.result = TestResultRequest.RESULT_FAIL
00149 r.text_summary = 'Mechanism didn\'t move. Check diagnostics.'
00150 r.html_result = "<p>No travel of mechanism, hysteresis did not complete. Check controller gains and encoder.</p><p>Test status: <b>FAIL</b>.</p>"
00151 r.html_result += '<p align=center><b>Test Parameters</b></p>\n'
00152 self.send_results(r)
00153 return
00154
00155 pos_data = HysteresisDirectionData(self.data.position_up, self.data.effort_up, self.data.velocity_up)
00156 neg_data = HysteresisDirectionData(self.data.position_down, self.data.effort_down, self.data.velocity_down)
00157 hyst_data = HysteresisTestData(pos_data, neg_data)
00158
00159
00160 if pos_data.position.size < 20 or neg_data.position.size < 20:
00161 r.result = TestResultRequest.RESULT_FAIL
00162 r.text_summary = 'Incomplete data set. Check diagnostics.'
00163 r.html_result = "<p>Not enough data in one or more directions.</p><p>Test Status: <b>FAIL</b>.</p><p>Test status: <b>FAIL</b>.</p>"
00164 r.html_result += '<p align=center><b>Test Parameters</b></p>\n'
00165 self.send_results(r)
00166 return
00167
00168
00169 range_result = range_analysis(params, hyst_data)
00170
00171 if params.slope == 0:
00172 effort_result = effort_analysis(params, hyst_data)
00173 else:
00174 effort_result = regression_analysis(params, hyst_data)
00175
00176 vel_result = velocity_analysis(params, hyst_data)
00177 vel_html = vel_result.html
00178
00179
00180 effort_plot = plot_effort(params, hyst_data)
00181 vel_plot = plot_velocity(params, hyst_data)
00182 r.plots = [effort_plot, vel_plot]
00183
00184 html = '<img src=\"IMG_PATH/%s.png\", width = 640, height = 480/>' % effort_plot.title
00185 html += '<p><b>Legend:</b> Red - Average Effort. Yellow - Error Bars. Green - Expected Effort.</p>\n'
00186 html += '<p align=center><b>Range Data</b></p>' + range_result.html + '<hr size="2">\n'
00187 html += '<p align=center><b>Effort Data</b></p>' + effort_result.html + '<hr size="2">\n'
00188
00189 html += '<p align=center><b>Velocity Data</b></p>'
00190 html += '<img src=\"IMG_PATH/%s.png\", width = 640, height = 480/>' % vel_plot.title
00191
00192 html += vel_html + '<hr size="2">\n'
00193 html += '<p align=center><b>Test Parameters</b></p>\n'
00194
00195
00196 r.html_result = html
00197
00198 r.values.extend(effort_result.values)
00199 r.values.extend(range_result.values)
00200 r.values.extend(vel_result.values)
00201
00202 if range_result.result and effort_result.result:
00203 r.text_summary = 'Hysteresis result: OK'
00204 r.result = TestResultRequest.RESULT_PASS
00205 elif not range_result.result:
00206 r.text_summary = 'Hysteresis range failed. Joint did not complete range of motion.'
00207 r.result = TestResultRequest.RESULT_FAIL
00208 else:
00209 r.text_summary = 'Hysteresis result: Questionable. ' + range_result.summary + ' ' + effort_result.summary
00210 r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
00211
00212 self.send_results(r)
00213 except Exception, e:
00214 rospy.logerr('hysteresis_plot caught exception, returning test failure.')
00215 rospy.logerr(traceback.format_exc())
00216 self.test_failed_service_call(traceback.format_exc())
00217
00218
00219 if __name__ == "__main__":
00220 try:
00221 app = AnalysisApp()
00222 my_rate = rospy.Rate(5)
00223 while not rospy.is_shutdown() and not app.has_data():
00224 my_rate.sleep()
00225
00226 if not rospy.is_shutdown():
00227 app.hysteresis_plot()
00228 rospy.spin()
00229 except KeyboardInterrupt:
00230 pass
00231 except Exception, e:
00232 traceback.print_exc()
00233