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 PKG = 'qualification'
00031 import roslib; roslib.load_manifest(PKG)
00032
00033 import qualification.analysis.hysteresis_analysis as hyst_analysis
00034
00035 import rostest, unittest
00036
00037 import math, numpy
00038 import sys, os
00039 import copy
00040
00041 import random
00042 random.seed()
00043
00044 class DummyWristRollHysteresisTestData(hyst_analysis.HysteresisTestData):
00045 def __init__(self, pos_data, neg_data):
00046 hyst_analysis.HysteresisTestData.__init__(self, pos_data, neg_data)
00047
00048 self.pos_flex_effort = numpy.array([ 0.0 for x in pos_data.position ])
00049 self.neg_flex_effort = numpy.array([ 0.0 for x in neg_data.position ])
00050
00051
00052 class TestHysteresis(unittest.TestCase):
00053 def setUp(self):
00054 self.pos_position = [ 0.001 * i for i in range(-1100, 1100)]
00055 self.neg_position = [-0.001 * i for i in range(-1100, 1100)]
00056
00057 self.pos_velocity = [ 0.5 for i in range(-1100, 1100)]
00058 self.neg_velocity = [-0.5 for i in range(-1100, 1100)]
00059
00060 self.pos_effort = [ 1.0 for i in range(-1100, 1100)]
00061 self.neg_effort = [-1.0 for i in range(-1100, 1100)]
00062
00063
00064 self.pos_data = hyst_analysis.HysteresisDirectionData(self.pos_position, self.pos_effort, self.pos_velocity)
00065 self.neg_data = hyst_analysis.HysteresisDirectionData(self.neg_position, self.neg_effort, self.neg_velocity)
00066
00067 self.data = hyst_analysis.HysteresisTestData(self.pos_data, self.neg_data)
00068
00069
00070 self.params = hyst_analysis.HysteresisParameters()
00071 self.params.pos_effort = 1.0
00072 self.params.neg_effort = -1.0
00073 self.params.range_max = 1.0
00074 self.params.range_min = -1.0
00075 self.params.velocity = 0.5
00076 self.params.tolerance = 0.1
00077 self.params.sd_max = 0.2
00078 self.params.slope = 0.0
00079 self.params.joint_name = "dummy_jnt"
00080
00081
00082 self.wrist_roll_data = DummyWristRollHysteresisTestData(self.pos_data, self.neg_data)
00083
00084
00085 self.wrist_roll_params = copy.deepcopy(self.params)
00086 self.wrist_roll_params.flex_joint = 'wrist_flx_jnt'
00087 self.wrist_roll_params.flex_tol = 0.5
00088 self.wrist_roll_params.flex_max = 1.0
00089 self.wrist_roll_params.flex_sd = 0.25
00090 self.wrist_roll_params.flex_p_gain = 1.0
00091 self.wrist_roll_params.flex_i_gain = 1.0
00092 self.wrist_roll_params.flex_d_gain = 1.0
00093 self.wrist_roll_params.flex_i_clamp = 1.0
00094
00095 def test_range(self):
00096
00097 good = hyst_analysis.range_analysis(self.params, self.data)
00098 self.assert_(good.result, "Hystersis range result didn't pass: %s\n%s" % (good.summary, good.html))
00099
00100
00101 bad_params = copy.deepcopy(self.params)
00102 bad_params.range_max = max(self.pos_position) + 0.1
00103 bad_params.range_min = min(self.pos_position) - 0.1
00104
00105 bad = hyst_analysis.range_analysis(bad_params, self.data)
00106 self.assert_(not bad.result, "Hysteresis didn't fail for invalid range. Message: %s\n%s" % (bad.summary, bad.html))
00107
00108
00109 cont_range = copy.deepcopy(self.params)
00110 cont_range.range_max = 0.0
00111 cont_range.range_min = 0.0
00112
00113 cont = hyst_analysis.range_analysis(cont_range, self.data)
00114 self.assert_(cont.result, "Continuous result failed! Summary: %s" % cont.summary)
00115 self.assert_(cont.summary.lower().find('continuous') > -1, "Continuous check failed to pick up that it was continuous. Summary: %s\n%s" % (cont.summary, cont.html))
00116
00117
00118 def test_effort(self):
00119
00120 good = hyst_analysis.range_analysis(self.params, self.data)
00121 self.assert_(good.result, "Hystersis effort result didn't pass: %s" % good.summary)
00122
00123
00124 pos_high_effort = [ x + 0.5 for x in self.pos_effort ]
00125 neg_high_effort = [ x - 0.5 for x in self.neg_effort ]
00126 pos_high_data = hyst_analysis.HysteresisDirectionData(self.pos_position, pos_high_effort, self.pos_velocity)
00127 neg_high_data = hyst_analysis.HysteresisDirectionData(self.neg_position, neg_high_effort, self.neg_velocity)
00128
00129 high_effort_data = hyst_analysis.HysteresisTestData(pos_high_data, neg_high_data)
00130
00131 high = hyst_analysis.effort_analysis(self.params, high_effort_data)
00132 self.assert_(not high.result, "Effort didn't fail for high effort! %s\n%s" % (high.summary, high.html))
00133
00134
00135 pos_uneven_effort = [ random.gauss(x, 0.5 * x) for x in self.pos_effort ]
00136 neg_uneven_effort = [ random.gauss(x, 0.5 * x) for x in self.neg_effort ]
00137
00138
00139 noisy = numpy.std(pos_uneven_effort) > self.params.sd_max or numpy.std(neg_uneven_effort) > self.params.sd_max
00140
00141 pos_uneven_data = hyst_analysis.HysteresisDirectionData(self.pos_position, pos_uneven_effort, self.pos_velocity)
00142 neg_uneven_data = hyst_analysis.HysteresisDirectionData(self.neg_position, neg_uneven_effort, self.neg_velocity)
00143
00144 uneven_effort_data = hyst_analysis.HysteresisTestData(pos_uneven_data, neg_uneven_data)
00145
00146 uneven = hyst_analysis.effort_analysis(self.params, uneven_effort_data)
00147 self.assert_(noisy and not uneven.result, "Effort didn't fail for uneven effort, but was noisy! %s\n%s" % (uneven.summary, uneven.html))
00148
00149
00150 def test_velocity(self):
00151
00152 rv = hyst_analysis.velocity_analysis(self.params, self.data)
00153 self.assert_(rv.result, "Velocity failed: %s\n%s" % (rv.summary, rv.html))
00154
00155
00156 def test_slope(self):
00157
00158 slope_params = copy.deepcopy(self.params)
00159 slope_params.slope = 1.0
00160 slope_params.pos_effort = 1.0
00161 slope_params.neg_effort = -1.0
00162
00163 pos_slope_effort = [ x * slope_params.slope + slope_params.pos_effort for x in self.pos_position ]
00164 neg_slope_effort = [ x * slope_params.slope + slope_params.neg_effort for x in self.neg_position ]
00165
00166
00167 pos_slope_data = hyst_analysis.HysteresisDirectionData(self.pos_position, pos_slope_effort, self.pos_velocity)
00168 neg_slope_data = hyst_analysis.HysteresisDirectionData(self.neg_position, neg_slope_effort, self.neg_velocity)
00169
00170
00171 slope_data = hyst_analysis.HysteresisTestData(pos_slope_data, neg_slope_data)
00172
00173 rv = hyst_analysis.regression_analysis(slope_params, slope_data)
00174 self.assert_(rv.result, "Slope check failed: %s\n%s" % (rv.summary, rv.html))
00175
00176 def test_plots(self):
00177
00178 p_eff = hyst_analysis.plot_effort(self.params, self.data)
00179 p_vel = hyst_analysis.plot_velocity(self.params, self.data)
00180
00181 def test_wrist_analysis(self):
00182
00183 self.assert_(hyst_analysis.wrist_hysteresis_data_present(self.wrist_roll_data), "Unable to confirm that wrist data was valid. Should have valid data")
00184
00185
00186 flex_analysis = hyst_analysis.wrist_flex_analysis(self.wrist_roll_params, self.wrist_roll_data)
00187 self.assert_(flex_analysis.result, "Wrist flex analysis failed! %s\n%s" % (flex_analysis.summary,
00188 flex_analysis.html))
00189
00190
00191 p = hyst_analysis.plot_flex_effort(self.wrist_roll_params, self.wrist_roll_data)
00192
00193
00194 if __name__ == '__main__':
00195 rostest.unitrun(PKG, 'check_hysteresis', TestHysteresis)
00196
00197