joint_chain_unittest.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of Willow Garage, Inc. nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 
34 
35 import roslib; roslib.load_manifest('calibration_estimation')
36 
37 import sys
38 import unittest
39 import rospy
40 import time
41 import numpy
42 import yaml
43 
44 from calibration_estimation.joint_chain import JointChain
45 from calibration_estimation.single_transform import SingleTransform
46 from calibration_estimation.urdf_params import UrdfParams
47 from sensor_msgs.msg import JointState
48 
49 class LoadJointChain(unittest.TestCase):
50  def setUp(self):
51  print ""
52  config = '''
53 root: x
54 tip: y
55 joints: [j1, j2, j3]
56 active_joints: [j1, j2, j3]
57 axis: [6, 6, 6]
58 gearing: [1, 1, 1]
59 cov:
60  joint_angles: [1, 1, 1]
61 '''
62  config_dict = yaml.load(config)
63  config_dict['transforms'] = { 'j1': SingleTransform([1, 0, 0, 0, 0, 0]),
64  'j2': SingleTransform([1, 0, 0, 0, 0, 0]),
65  'j3': SingleTransform([1, 0, 2, 0, 0, 0]) }
66 
67  self.chain = JointChain(config_dict)
68 
70  def test_init(self):
71  pass
72 
73  def test_get_length(self):
74  self.assertEqual(self.chain.get_length(), 3)
75 
76  def test_free(self):
77  free_config = [ [ 1, 0, 0, 0, 0, 0 ],
78  [ 1, 0, 0, 0, 0, 0 ],
79  [ 1, 0, 0, 0, 0, 1 ] ]
80 
81  free_list = self.chain.calc_free({'transforms':free_config, 'axis': [6,6,6], 'gearing':[0,0,0]})
82  self.assertEqual(free_list[0], 0)
83  self.assertEqual(free_list[1], 0)
84  self.assertEqual(free_list[2], 0)
85 
86  def test_deflate(self):
87  param_vec = self.chain.deflate()
88  self.assertEqual(param_vec[0,0], 1)
89  self.assertEqual(param_vec[1,0], 1)
90  self.assertEqual(param_vec[2,0], 1)
91 
92  def test_inflate(self):
93  param_vec = numpy.reshape(numpy.matrix(numpy.arange(3)),(3,1))
94  self.chain.inflate(param_vec)
95  self.assertEqual(self.chain._gearing[0], 0)
96  self.assertEqual(self.chain._gearing[2], 2)
97 
98  def test_to_params(self):
99  param_vec = self.chain.deflate()
100  param_vec[0,0] = 10
101  config = self.chain.params_to_config(param_vec)
102  self.assertAlmostEqual(config['gearing'][0], 10, 6)
103 
104  def test_fk_easy1(self):
105  chain_state = JointState()
106  chain_state.position = [0, 0, 0]
107  eef = self.chain.fk(chain_state, 0)
108  eef_expected = numpy.matrix( [[ 1, 0, 0, 1],
109  [ 0, 1, 0, 0],
110  [ 0, 0, 1, 0],
111  [ 0, 0, 0, 1]] )
112  self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
113 
114  def test_fk_easy2(self):
115  chain_state = JointState()
116  chain_state.position = [numpy.pi/2, 0, 0]
117  eef = self.chain.fk(chain_state, 0)
118  print eef
119  eef_expected = numpy.matrix( [[ 0,-1, 0, 1],
120  [ 1, 0, 0, 0],
121  [ 0, 0, 1, 0],
122  [ 0, 0, 0, 1]] )
123  self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
124 
125  def test_fk_easy3(self):
126  chain_state = JointState()
127  chain_state.position = [numpy.pi/2, numpy.pi/2, 0]
128  eef = self.chain.fk(chain_state, 1)
129  print eef
130  eef_expected = numpy.matrix( [[-1, 0, 0, 1],
131  [ 0,-1, 0, 1],
132  [ 0, 0, 1, 0],
133  [ 0, 0, 0, 1]] )
134  self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
135 
136  def test_fk_easy4(self):
137  chain_state = JointState()
138  chain_state.position = [0, 0, 0]
139  eef = self.chain.fk(chain_state, -1)
140  print eef
141  eef_expected = numpy.matrix( [[ 1, 0, 0, 3],
142  [ 0, 1, 0, 0],
143  [ 0, 0, 1, 2],
144  [ 0, 0, 0, 1]] )
145  self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
146 
147 if __name__ == '__main__':
148  import rostest
149  rostest.unitrun('calibration_estimation', 'test_JointChain', TestJointChain, coverage_packages=['calibration_estimation.joint_chain'])


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Thu Jun 6 2019 19:17:16