cb_analysis_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) 2010, 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 ##\brief Unit tests of counterbalance analysis code
36 
37 from __future__ import division
38 
39 PKG = 'pr2_counterbalance_check'
40 import roslib
41 
43 
44 import copy
45 import os, sys
46 import rostest, unittest
47 
48 # Dummy classes to store data
49 class DummyCBAnalysisParams(object): pass
50 class DummyCBAnalysisData(object): pass
51 class DummyCBRunAnalysisData(object): pass
52 class DummyCBPositionAnalysisData(object): pass
53 class DummyJointPositionAnalysisData(object): pass
54 
55 def get_position(minv, maxv, num_pts, i):
56  return minv + (maxv - minv) * i / num_pts
57 
58 def generate_data(params):
59  data = DummyCBAnalysisData()
60  data.lift_data = []
61  for i in range(params.num_lifts):
62  lift_data = DummyCBRunAnalysisData()
63  lift_data.lift_position = get_position(params.min_lift, params.max_lift, params.num_lifts, i)
64  lift_data.flex_data = []
65 
66  for j in range(params.num_flexes):
68  fd.flex_position = get_position(params.min_flex, params.max_flex, params.num_flexes, j)
69 
70  fd.lift_hold = DummyJointPositionAnalysisData()
71  fd.lift_hold.position_avg = lift_data.lift_position
72  fd.lift_hold.position_sd = 0.0
73  fd.lift_hold.effort_avg = j / 100.0 - params.num_flexes/200.0
74  fd.lift_hold.effort_sd = 0.0
75 
76  fd.flex_hold = DummyJointPositionAnalysisData()
77  fd.flex_hold.position_avg = fd.flex_position
78  fd.flex_hold.position_sd = 0.0
79  fd.flex_hold.effort_avg = j / 100.0 - params.num_flexes/200.0
80  fd.flex_hold.effort_sd = 0.0
81 
82  lift_data.flex_data.append(fd)
83 
84  data.lift_data.append(lift_data)
85 
86  return data
87 
88 class TestCounterbalanceAnalysis(unittest.TestCase):
89  def setUp(self):
90  # Set up parameters
92  self.params.lift_dither = 5.0
93  self.params.flex_dither = 5.0
94  self.params.lift_joint = 'lift_joint'
95  self.params.flex_joint = 'flex_joint'
96  self.params.timeout_hit = False
97  self.params.flex_test = True # Set to False for lift-only test
98  self.params.lift_mse = 1.0
99  self.params.lift_avg_abs = 1.0
100  self.params.lift_avg_eff = 1.0
101  self.params.flex_mse = 1.0
102  self.params.flex_avg_abs = 1.0
103  self.params.flex_avg_eff = 1.0
104 
105  self.params.screw_tol = 2.0
106  self.params.bar_tol = 0.8
107 
108  self.params.num_lifts = 8
109  self.params.min_lift = -0.2
110  self.params.max_lift = 1.2
111 
112  self.params.num_flexes = 9
113  self.params.min_flex = -1.8
114  self.params.max_flex = -0.2
115 
116  # Set up data
117  self.data = generate_data(self.params)
118 
119  # Model file for analyzing data
120  self.model_file = os.path.join(roslib.packages.get_pkg_dir(PKG), 'cb_data/counterbalance_model.dat')
121 
122 
123  def test_lift_effort(self):
124  result = analyze_lift_efforts(self.params, self.data)
125  self.assert_(result.result, "Lift effort result wasn't OK. %s\n%s" % (result.summary, result.html))
126 
127  def test_flex_effort(self):
128  result = analyze_flex_efforts(self.params, self.data)
129  self.assert_(result.result, "Flex effort result wasn't OK. %s\n%s" % (result.summary, result.html))
130 
131 
132 
133 
134  def test_adjustment(self):
135  """
136  Test that CB adjustment runs successfully
137  """
138  (secondary, bar) = calc_cb_adjust(self.data, self.model_file)
139 
140  self.assert_(abs(secondary) < self.params.screw_tol and abs(bar) < self.params.bar_tol,
141  "Calculated adjustment didn't match. Adjustment: %.2f, %.2f" % (secondary, bar))
142 
143  adjust_result = check_cb_adjustment(self.params, self.data, self.model_file)
144  self.assert_(adjust_result.result, "Adjustment result was unsuccessful! %s\n%s" % (adjust_result.summary, adjust_result.html))
145 
146  # Bad data has invalid number of dimensions
147  bad_params = copy.deepcopy(self.params)
148  bad_params.num_lifts = 7
149  bad_params.max_lift = 1.0
150 
151  bad_data = generate_data(bad_params)
152 
153  (secondary, bar) = calc_cb_adjust(bad_data, self.model_file)
154 
155  self.assert_(abs(secondary) > 50 and abs(bar) > 50,
156  "Calculated adjustment successful on bad data. Adjustment: %.2f, %.2f" % (secondary, bar))
157 
158 
159  def test_plots(self):
160  p_contout_lift = plot_effort_contour(self.params, self.data, True)
161  p_contout_flex = plot_effort_contour(self.params, self.data, False)
162 
163  p_eff = plot_efforts_by_lift_position(self.params, self.data)
164 
165 
166 if __name__ == '__main__':
167  rostest.unitrun(PKG, 'test_cb_analysis', TestCounterbalanceAnalysis)
def analyze_lift_efforts(params, data)
Checks shoulder lift efforts against params.
def generate_data(params)
def get_position(minv, maxv, num_pts, i)
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 calc_cb_adjust(data, model_file)
Calculates CB adjustment.
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