wrist_diff_analysis.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright (c) 2009, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #     * Redistributions of source code must retain the above copyright
00010 #       notice, this list of conditions and the following disclaimer.
00011 #     * Redistributions in binary form must reproduce the above copyright
00012 #       notice, this list of conditions and the following disclaimer in the
00013 #       documentation and/or other materials provided with the distribution.
00014 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00015 #       contributors may be used to endorse or promote products derived from
00016 #       this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 ##\author Kevin Watts
00031 
00032 PKG = "qualification"
00033 
00034 import roslib; roslib.load_manifest(PKG)
00035 
00036 import rospy
00037 
00038 from pr2_self_test_msgs.srv import TestResult, TestResultRequest
00039 from qualification.analysis.hysteresis_analysis import *
00040 
00041 from joint_qualification_controllers.msg import WristDiffData
00042 
00043 import traceback
00044 
00045 class WristDiffAnalysis:
00046     def __init__(self):
00047         self._msg = None
00048         self.data_sent = False
00049         rospy.init_node('wrist_diff_analysis')
00050         self.data_srv = rospy.Subscriber('/test_data', WristDiffData, self.on_wrist_data)
00051         self.result_service = rospy.ServiceProxy('test_result', TestResult)
00052         
00053     def has_data(self):
00054         return self._msg is not None
00055 
00056     def test_failed_service_call(self, except_str = ''):
00057         rospy.logerr(except_str)
00058         r = TestResultRequest()
00059         r.html_result = except_str
00060         r.text_summary = 'Caught exception, automated test failure.'
00061         r.plots = []
00062         r.result = TestResultRequest.RESULT_FAIL
00063         self.send_results(r)
00064 
00065     def send_results(self, test_result):
00066         if not self.data_sent:
00067             rospy.wait_for_service('test_result', 5)
00068             self.result_service.call(test_result)
00069             self.data_sent = True
00070 
00071     def on_wrist_data(self, msg):
00072         self._msg = msg
00073 
00074     def analyze_wrist_data(self):
00075         r = TestResultRequest()
00076         r.html_result = ''
00077         r.text_summary = 'No data.'
00078         r.plots = []
00079         r.result = TestResultRequest.RESULT_FAIL
00080 
00081         params = WristRollHysteresisParams(self._msg)
00082         r.params = params.get_test_params()
00083 
00084         if self._msg.timeout:
00085             r.text_summary = 'Wrist difference controller timed out'
00086             r.result = TestResultRequest.RESULT_FAIL
00087             self.send_results(r)
00088             return 
00089 
00090         data = WristRollHysteresisTestData(self._msg)
00091 
00092         if not wrist_hysteresis_data_present(data):
00093             r.text_summary = 'Wrist difference controller didn\'t generate enough data.'
00094             r.result = TestResultRequest.RESULT_FAIL
00095             self.send_results(r)
00096             return 
00097 
00098         # Normal hysteresis analysis on roll
00099         roll_result = effort_analysis(params, data)
00100         # Check flex efforts 
00101         flex_result = wrist_flex_analysis(params, data)
00102 
00103         roll_plot = plot_effort(params, data)
00104         flex_plot = plot_flex_effort(params, data)
00105         r.plots.append(roll_plot)
00106         r.plots.append(flex_plot)
00107         
00108         r.text_summary = make_wrist_test_summary(roll_result.result, flex_result.result)
00109 
00110         if roll_result.result and flex_result.result:
00111             r.result = TestResultRequest.RESULT_PASS
00112         elif flex_result.result: ##\todo Remove this after first 5 units
00113             r.result = TestResultRequest.RESULT_HUMAN_REQUIRED
00114         else:
00115             r.result = TestResultRequest.RESULT_FAIL
00116 
00117         result_html = ['<H4 align=center>Flex Effort</H4>']
00118         result_html.append('<p>Flex effort should be close to zero during roll hysteresis.</p>')
00119         result_html.append('<img src=\"IMG_PATH/%s.png\", width = 640, height = 480/>' % flex_plot.title)
00120         result_html.append(flex_result.html)
00121         result_html.append('<hr size="2">')
00122         result_html.append('<H4 align=center>Roll Hysteresis</H4>')
00123         result_html.append('<p>Wrist roll hysteresis. The efforts should be close to the expected values.</p>')
00124         result_html.append('<img src=\"IMG_PATH/%s.png\", width = 640, height = 480/>' % roll_plot.title)
00125         result_html.append(roll_result.html)
00126         result_html.append('<hr size="2">')
00127 
00128         r.html_result = '\n'.join(result_html)
00129 
00130         r.values = roll_result.values + flex_result.values
00131 
00132         self.send_results(r)
00133          
00134 if __name__ == '__main__':
00135     wda = WristDiffAnalysis()
00136     my_rate = rospy.Rate(5)
00137     try:
00138         while not rospy.is_shutdown() and not wda.has_data():
00139             my_rate.sleep()
00140 
00141         if not rospy.is_shutdown():
00142             wda.analyze_wrist_data()
00143     except KeyboardInterrupt, e:
00144         pass
00145     except:
00146         rospy.logerr("Exception in analysis: %s", traceback.format_exc())
00147         wda.test_failed_service_call(traceback.format_exc())


qualification
Author(s): Kevin Watts (watts@willowgarage.com), Josh Faust (jfaust@willowgarage.com)
autogenerated on Sat Dec 28 2013 17:57:34