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
00043 from calibration_estimation.single_transform import SingleTransform
00044 from numpy import *
00045
00046 class TestSingleTransform(unittest.TestCase):
00047
00048 def test_free(self):
00049
00050 st = SingleTransform([0, 0, 0, 0, 0, 0])
00051 free_list = st.calc_free( [0, 0, 1, 1, 0, 0] )
00052
00053 self.assertEqual(free_list[0], False)
00054 self.assertEqual(free_list[1], False)
00055 self.assertEqual(free_list[2], True)
00056 self.assertEqual(free_list[3], True)
00057 self.assertEqual(free_list[4], False)
00058 self.assertEqual(free_list[5], False)
00059
00060 def test_inflate(self):
00061 st = SingleTransform([0, 0, 0, 0, 0, 0])
00062 st.inflate( reshape( matrix([1, 0, 0, 0, 0, 0], float), (-1,1) ))
00063 expected = numpy.matrix( [[ 1, 0, 0, 1],
00064 [ 0, 1, 0, 0],
00065 [ 0, 0, 1, 0],
00066 [ 0, 0, 0, 1]], float )
00067
00068 print ""
00069 print st.transform
00070
00071 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected), 0.0, 6)
00072
00073 def test_deflate(self):
00074 st = SingleTransform([0, 0, 0, 0, 0, 0])
00075 p = reshape( matrix([1, 0, 0, 0, 0, 0], float), (-1,1) )
00076 st.inflate(p)
00077 result = st.deflate()
00078 self.assertAlmostEqual(numpy.linalg.norm(p-result), 0.0, 6)
00079
00080 def test_params_to_config(self):
00081 st = SingleTransform()
00082 p = reshape( matrix([1, 0, 0, 0, 0, 0], float), (-1,1) )
00083 config = st.params_to_config(p)
00084 self.assertAlmostEqual( config[0], 1, 6)
00085 self.assertAlmostEqual( config[1], 0, 6)
00086
00087
00088 def test_easy_trans_1(self):
00089 st = SingleTransform([1, 2, 3, 0, 0, 0])
00090 expected = numpy.matrix( [[ 1, 0, 0, 1],
00091 [ 0, 1, 0, 2],
00092 [ 0, 0, 1, 3],
00093 [ 0, 0, 0, 1]], float )
00094
00095 print ""
00096 print st.transform
00097
00098 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected), 0.0, 6)
00099
00100 def test_easy_rot_1(self):
00101 st = SingleTransform([0, 0, 0, 0, 0, pi/2])
00102 expected = numpy.matrix( [[ 0,-1, 0, 0],
00103 [ 1, 0, 0, 0],
00104 [ 0, 0, 1, 0],
00105 [ 0, 0, 0, 1]], float )
00106 print ""
00107 print st.transform
00108
00109 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected), 0.0, 6)
00110
00111 def test_easy_rot_2(self):
00112 st = SingleTransform([0, 0, 0, 0, pi/2, 0])
00113 expected = numpy.matrix( [[ 0, 0, 1, 0],
00114 [ 0, 1, 0, 0],
00115 [-1, 0, 0, 0],
00116 [ 0, 0, 0, 1]], float )
00117 print ""
00118 print st.transform
00119
00120 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected), 0.0, 6)
00121
00122 def test_easy_rot_3(self):
00123 st = SingleTransform([0, 0, 0, pi/2, 0, 0])
00124 expected = numpy.matrix( [[ 1, 0, 0, 0],
00125 [ 0, 0,-1, 0],
00126 [ 0, 1, 0, 0],
00127 [ 0, 0, 0, 1]], float )
00128 print ""
00129 print st.transform
00130
00131 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected), 0.0, 6)
00132
00133 def test_length(self):
00134 st = SingleTransform([0, 0, 0, 0, 0, 0])
00135 self.assertEqual(st.get_length(), 6)
00136
00137 def test_hard(self):
00138 sample_nums = range(1,6)
00139 params_filenames = ["test/data/single_transform_data/params_%02u.txt" % n for n in sample_nums]
00140 transform_filenames = ["test/data/single_transform_data/transform_%02u.txt" % n for n in sample_nums]
00141
00142 for params_filename, transform_filename in zip(params_filenames, transform_filenames):
00143 f_params = open(params_filename)
00144 f_transforms = open(transform_filename)
00145 param_elems = [float(x) for x in f_params.read().split()]
00146 transform_elems = [float(x) for x in f_transforms.read().split()]
00147
00148 st = SingleTransform(param_elems)
00149 expected_result = numpy.matrix(transform_elems)
00150 expected_result.shape = 4,4
00151
00152 self.assertAlmostEqual(numpy.linalg.norm(st.transform-expected_result), 0.0, 4, "Failed on %s" % params_filename)
00153
00154 if __name__ == '__main__':
00155 import rostest
00156 rostest.unitrun('pr2_calibration_estimation', 'test_SingleTransform', TestSingleTransform, coverage_packages=['pr2_calibration_estimation.single_transform'])
00157