camera_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 
43 from calibration_estimation.camera import RectifiedCamera
44 from numpy import *
45 
47  return {'baseline_shift':0,
48  'frame_id': 'default_frame',
49  'chain_id': 'default_chain',
50  'f_shift':0,
51  'cx_shift':0,
52  'cy_shift':0,
53  'cov': {'u':0.5, 'v':0.5} }
54 
55 class TestRectifiedCamera(unittest.TestCase):
56 
59  P_list = [ 1, 0, 0, 0, \
60  0, 1, 0, 0, \
61  0, 0, 1, 0 ]
62 
63  pts = matrix( [ [ 0, 1, 0, 2 ],
64  [ 0, 1, 1, 0 ],
65  [ 1, 1, 2, 2 ],
66  [ 1, 1, 1, 1 ]], float )
67 
68  expected = matrix( [ [ 0, 1, 0, 1],
69  [ 0, 1, .5, 0] ] )
70 
71  result = cam.project(P_list, pts)
72 
73  print ""
74  print result
75 
76  self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
77 
80  P_list = [ 1, 0, 0,-1, \
81  0, 1, 0, 0, \
82  0, 0, 1, 0 ]
83 
84  pts = matrix( [ [ 0, 1, 0, 2 ],
85  [ 0, 1, 1, 0 ],
86  [ 1, 1, 2, 2 ],
87  [ 1, 1, 1, 1 ]], float )
88 
89  expected = matrix( [ [-1, 0,-.5,.5],
90  [ 0, 1, .5, 0] ] )
91 
92  result = cam.project(P_list, pts)
93 
94  print ""
95  print result
96 
97  self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
98 
101  P_list = [ 1, 0, 0, 0, \
102  0, 1, 0, 0, \
103  0, 0, 1, 0 ]
104 
105  cam.inflate(matrix([-1]))
106 
107  pts = matrix( [ [ 0, 1, 0, 2 ],
108  [ 0, 1, 1, 0 ],
109  [ 1, 1, 2, 2 ],
110  [ 1, 1, 1, 1 ]], float )
111 
112  expected = matrix( [ [-1, 0,-.5,.5],
113  [ 0, 1, .5, 0] ] )
114 
115  result = cam.project(P_list, pts)
116 
117  print ""
118  print result
119 
120  self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
121 
122 
123  def test_free(self):
125  free_list = cam.calc_free( {"baseline_shift":0, "f_shift":0, "cx_shift":0, "cy_shift":0} )
126  self.assertEqual(free_list[0], False)
127 
128  free_list = cam.calc_free( {"baseline_shift":1, "f_shift":0, "cx_shift":0, "cy_shift":0} )
129  self.assertEqual(free_list[0], True)
130 
131  self.assertEqual(len(free_list), 4)
132 
135  p = matrix([1, 0, 0, 0], float).T
136  config = cam.params_to_config(p)
137  self.assertAlmostEqual(config["baseline_shift"], 1, 6)
138 
139  def test_length(self):
141  self.assertEqual(cam.get_length(), 4)
142 
143  def test_deflate(self):
144  params = DefaultParams()
145  params['baseline_shift'] = 10
146  cam = RectifiedCamera(params)
147  self.assertEqual(cam.deflate()[0,0], 10)
148 
149 if __name__ == '__main__':
150  import rostest
151  rostest.unitrun('calibration_estimation', 'test_RectifiedCamera', TestRectifiedCamera, coverage_packages=['calibration_estimation.camera'])
152 


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Thu Jun 6 2019 19:17:16