tilting_laser_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.tilting_laser import TiltingLaser
45 from calibration_estimation.urdf_params import UrdfParams
46 from numpy import *
47 
49  urdf = '''
50 <robot>
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"/>
56  </joint>
57  <link name="j0_link"/>
58  <joint name="j1" type="revolute">
59  <axis xyz="0 0 1"/>
60  <origin xyz="0 0 0" rpy="0 0 0"/>
61  <parent link="j0_link"/>
62  <child link="j1_link"/>
63  </joint>
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"/>
69  </joint>
70  <link name="j2_link"/>
71 </robot>
72 '''
73  config = yaml.load('''
74 sensors:
75  chains: {}
76  rectified_cams: {}
77  tilting_lasers:
78  test_laser:
79  joint: j1
80  frame_id: j2_link
81  gearing: 1.0
82  cov:
83  bearing: 0.0005
84  range: 0.005
85  tilt: 0.0005
86 transforms: {}
87 checkerboards: {}
88 ''')
89 
90  return UrdfParams(urdf, config)
91 
92 class TestTiltingLaser(unittest.TestCase):
93 
95  params = loadSystem1()
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
100  print ""
101  print result
102  self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
103 
105  params = loadSystem1()
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
110  print ""
111  print result
112  self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
113 
115  params = loadSystem1()
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
120  print ""
121  print result
122  self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
123 
125  params = loadSystem1()
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
130  print ""
131  print result
132  self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
133 
134  def test_project(self):
135  params = loadSystem1()
136  tl = params.tilting_lasers["test_laser"]
137  tl.update_config(params)
138 
139  result = tl.project_to_3D( [ [0, 0, 0],
140  [0, 0, 1],
141  [pi/2, 0, 0],
142  [pi/2, pi/2,1] ] )
143 
144  expected = numpy.matrix( [ [ 20, 21, 0, 0 ],
145  [ 0, 0, 0, 1 ],
146  [ 10, 10, -10, -10 ],
147  [ 1, 1, 1, 1 ] ] )
148 
149  print
150  print result
151 
152  self.assertAlmostEqual(numpy.linalg.norm(result - expected), 0.0, 6)
153 
154  def test_get_length(self):
155  params = loadSystem1()
156  tl = params.tilting_lasers["test_laser"]
157  self.assertEqual(tl.get_length(), 1)
158 
159 if __name__ == '__main__':
160  import rostest
161  rostest.unitrun('calibration_estimation', 'test_TiltingLaser', TestTiltingLaser, coverage_packages=['calibration_estimation.tilting_laser'])
162 


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Fri Apr 2 2021 02:12:53