35 import roslib; roslib.load_manifest(
'calibration_estimation')
51 <link name="base_link"/> 52 <joint name="j0" type="fixed"> 53 <origin xyz="0 0 10" rpy="0 0 0"/> 54 <parent link="base_link"/> 55 <child link="j0_link"/> 57 <link name="j0_link"/> 58 <joint name="j1" type="revolute"> 60 <origin xyz="0 0 0" rpy="0 0 0"/> 61 <parent link="j0_link"/> 62 <child link="j1_link"/> 64 <link name="j1_link"/> 65 <joint name="j2" type="fixed"> 66 <origin xyz="20 0 0" rpy="0 0 0"/> 67 <parent link="j1_link"/> 68 <child link="j2_link"/> 70 <link name="j2_link"/> 73 config = yaml.load(
''' 96 tl = params.tilting_lasers[
"test_laser"]
97 tl.update_config(params)
98 result = tl.project_point_to_3D([0, 0, 0])
99 expected = numpy.matrix( [20, 0, 10, 1] ).T
102 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
106 tl = params.tilting_lasers[
"test_laser"]
107 tl.update_config(params)
108 result = tl.project_point_to_3D([0, pi/2, 1])
109 expected = numpy.matrix( [20, 1, 10, 1] ).T
112 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
116 tl = params.tilting_lasers[
"test_laser"]
117 tl.update_config(params)
118 result = tl.project_point_to_3D([pi/2, 0, 0])
119 expected = numpy.matrix( [0 , 0,-10, 1] ).T
122 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
126 tl = params.tilting_lasers[
"test_laser"]
127 tl.update_config(params)
128 result = tl.project_point_to_3D([pi/2, -pi/2, 15])
129 expected = numpy.matrix( [0 ,-15, -10, 1] ).T
132 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
136 tl = params.tilting_lasers[
"test_laser"]
137 tl.update_config(params)
139 result = tl.project_to_3D( [ [0, 0, 0],
144 expected = numpy.matrix( [ [ 20, 21, 0, 0 ],
146 [ 10, 10, -10, -10 ],
152 self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
156 tl = params.tilting_lasers[
"test_laser"]
157 self.assertEqual(tl.get_length(), 1)
159 if __name__ ==
'__main__':
161 rostest.unitrun(
'calibration_estimation',
'test_TiltingLaser', TestTiltingLaser, coverage_packages=[
'calibration_estimation.tilting_laser'])
def test_project_point_easy_2(self)
def test_project_point_easy_4(self)
def test_get_length(self)
def test_project_point_easy_3(self)
def test_project_point_easy_1(self)