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 
00033 
00034 
00035 import roslib; roslib.load_manifest('calibration_estimation')
00036 
00037 import sys
00038 import unittest
00039 import rospy
00040 import time
00041 import numpy
00042 import yaml
00043 
00044 from calibration_estimation.joint_chain import JointChain
00045 from calibration_estimation.single_transform import SingleTransform
00046 from calibration_estimation.urdf_params import UrdfParams
00047 from sensor_msgs.msg import JointState
00048 
00049 class LoadJointChain(unittest.TestCase):
00050     def setUp(self):
00051         print ""
00052         config = '''
00053 root: x
00054 tip: y
00055 joints: [j1, j2, j3]
00056 active_joints: [j1, j2, j3]
00057 axis: [6, 6, 6]
00058 gearing: [1, 1, 1]
00059 cov:
00060   joint_angles: [1, 1, 1]
00061 '''
00062         config_dict = yaml.load(config)
00063         config_dict['transforms'] = { 'j1': SingleTransform([1, 0, 0, 0, 0, 0]),
00064                                       'j2': SingleTransform([1, 0, 0, 0, 0, 0]),
00065                                       'j3': SingleTransform([1, 0, 2, 0, 0, 0]) }
00066 
00067         self.chain = JointChain(config_dict)
00068 
00069 class TestJointChain(LoadJointChain):
00070     def test_init(self):
00071         pass
00072 
00073     def test_get_length(self):
00074         self.assertEqual(self.chain.get_length(), 3)
00075 
00076     def test_free(self):
00077         free_config = [ [ 1, 0, 0, 0, 0, 0 ],
00078                         [ 1, 0, 0, 0, 0, 0 ],
00079                         [ 1, 0, 0, 0, 0, 1 ] ]
00080 
00081         free_list = self.chain.calc_free({'transforms':free_config, 'axis': [6,6,6], 'gearing':[0,0,0]})
00082         self.assertEqual(free_list[0],  0)
00083         self.assertEqual(free_list[1],  0)
00084         self.assertEqual(free_list[2],  0)
00085 
00086     def test_deflate(self):
00087         param_vec = self.chain.deflate()
00088         self.assertEqual(param_vec[0,0], 1)
00089         self.assertEqual(param_vec[1,0], 1)
00090         self.assertEqual(param_vec[2,0], 1)
00091 
00092     def test_inflate(self):
00093         param_vec = numpy.reshape(numpy.matrix(numpy.arange(3)),(3,1))
00094         self.chain.inflate(param_vec)
00095         self.assertEqual(self.chain._gearing[0], 0)
00096         self.assertEqual(self.chain._gearing[2], 2)
00097 
00098     def test_to_params(self):
00099         param_vec = self.chain.deflate()
00100         param_vec[0,0] = 10
00101         config = self.chain.params_to_config(param_vec)
00102         self.assertAlmostEqual(config['gearing'][0], 10, 6)
00103 
00104     def test_fk_easy1(self):
00105         chain_state = JointState()
00106         chain_state.position = [0, 0, 0]
00107         eef = self.chain.fk(chain_state, 0)
00108         eef_expected = numpy.matrix( [[ 1, 0, 0, 1],
00109                                       [ 0, 1, 0, 0],
00110                                       [ 0, 0, 1, 0],
00111                                       [ 0, 0, 0, 1]] )
00112         self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
00113 
00114     def test_fk_easy2(self):
00115         chain_state = JointState()
00116         chain_state.position = [numpy.pi/2, 0, 0]
00117         eef = self.chain.fk(chain_state, 0)
00118         print eef
00119         eef_expected = numpy.matrix( [[ 0,-1, 0, 1],
00120                                       [ 1, 0, 0, 0],
00121                                       [ 0, 0, 1, 0],
00122                                       [ 0, 0, 0, 1]] )
00123         self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
00124 
00125     def test_fk_easy3(self):
00126         chain_state = JointState()
00127         chain_state.position = [numpy.pi/2, numpy.pi/2, 0]
00128         eef = self.chain.fk(chain_state, 1)
00129         print eef
00130         eef_expected = numpy.matrix( [[-1, 0, 0, 1],
00131                                       [ 0,-1, 0, 1],
00132                                       [ 0, 0, 1, 0],
00133                                       [ 0, 0, 0, 1]] )
00134         self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
00135 
00136     def test_fk_easy4(self):
00137         chain_state = JointState()
00138         chain_state.position = [0, 0, 0]
00139         eef = self.chain.fk(chain_state, -1)
00140         print eef
00141         eef_expected = numpy.matrix( [[ 1, 0, 0, 3],
00142                                       [ 0, 1, 0, 0],
00143                                       [ 0, 0, 1, 2],
00144                                       [ 0, 0, 0, 1]] )
00145         self.assertAlmostEqual(numpy.linalg.norm(eef-eef_expected), 0.0, 6)
00146 
00147 if __name__ == '__main__':
00148     import rostest
00149     rostest.unitrun('calibration_estimation', 'test_JointChain', TestJointChain, coverage_packages=['calibration_estimation.joint_chain'])