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.tilting_laser import TiltingLaser
00045 from calibration_estimation.urdf_params import UrdfParams
00046 from numpy import *
00047
00048 def loadSystem1():
00049 urdf = '''
00050 <robot>
00051 <link name="base_link"/>
00052 <joint name="j0" type="fixed">
00053 <origin xyz="0 0 10" rpy="0 0 0"/>
00054 <parent link="base_link"/>
00055 <child link="j0_link"/>
00056 </joint>
00057 <link name="j0_link"/>
00058 <joint name="j1" type="revolute">
00059 <axis xyz="0 0 1"/>
00060 <origin xyz="0 0 0" rpy="0 0 0"/>
00061 <parent link="j0_link"/>
00062 <child link="j1_link"/>
00063 </joint>
00064 <link name="j1_link"/>
00065 <joint name="j2" type="fixed">
00066 <origin xyz="20 0 0" rpy="0 0 0"/>
00067 <parent link="j1_link"/>
00068 <child link="j2_link"/>
00069 </joint>
00070 <link name="j2_link"/>
00071 </robot>
00072 '''
00073 config = yaml.load('''
00074 sensors:
00075 chains: {}
00076 rectified_cams: {}
00077 tilting_lasers:
00078 test_laser:
00079 joint: j1
00080 frame_id: j2_link
00081 gearing: 1.0
00082 cov:
00083 bearing: 0.0005
00084 range: 0.005
00085 tilt: 0.0005
00086 transforms: {}
00087 checkerboards: {}
00088 ''')
00089
00090 return UrdfParams(urdf, config)
00091
00092 class TestTiltingLaser(unittest.TestCase):
00093
00094 def test_project_point_easy_1(self):
00095 params = loadSystem1()
00096 tl = params.tilting_lasers["test_laser"]
00097 tl.update_config(params)
00098 result = tl.project_point_to_3D([0, 0, 0])
00099 expected = numpy.matrix( [20, 0, 10, 1] ).T
00100 print ""
00101 print result
00102 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
00103
00104 def test_project_point_easy_2(self):
00105 params = loadSystem1()
00106 tl = params.tilting_lasers["test_laser"]
00107 tl.update_config(params)
00108 result = tl.project_point_to_3D([0, pi/2, 1])
00109 expected = numpy.matrix( [20, 1, 10, 1] ).T
00110 print ""
00111 print result
00112 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
00113
00114 def test_project_point_easy_3(self):
00115 params = loadSystem1()
00116 tl = params.tilting_lasers["test_laser"]
00117 tl.update_config(params)
00118 result = tl.project_point_to_3D([pi/2, 0, 0])
00119 expected = numpy.matrix( [0 , 0,-10, 1] ).T
00120 print ""
00121 print result
00122 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
00123
00124 def test_project_point_easy_4(self):
00125 params = loadSystem1()
00126 tl = params.tilting_lasers["test_laser"]
00127 tl.update_config(params)
00128 result = tl.project_point_to_3D([pi/2, -pi/2, 15])
00129 expected = numpy.matrix( [0 ,-15, -10, 1] ).T
00130 print ""
00131 print result
00132 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
00133
00134 def test_project(self):
00135 params = loadSystem1()
00136 tl = params.tilting_lasers["test_laser"]
00137 tl.update_config(params)
00138
00139 result = tl.project_to_3D( [ [0, 0, 0],
00140 [0, 0, 1],
00141 [pi/2, 0, 0],
00142 [pi/2, pi/2,1] ] )
00143
00144 expected = numpy.matrix( [ [ 20, 21, 0, 0 ],
00145 [ 0, 0, 0, 1 ],
00146 [ 10, 10, -10, -10 ],
00147 [ 1, 1, 1, 1 ] ] )
00148
00149 print
00150 print result
00151
00152 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
00153
00154 def test_get_length(self):
00155 params = loadSystem1()
00156 tl = params.tilting_lasers["test_laser"]
00157 self.assertEqual(tl.get_length(), 1)
00158
00159 if __name__ == '__main__':
00160 import rostest
00161 rostest.unitrun('calibration_estimation', 'test_TiltingLaser', TestTiltingLaser, coverage_packages=['calibration_estimation.tilting_laser'])
00162