$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 00034 00035 import roslib; roslib.load_manifest('pr2_calibration_estimation') 00036 00037 import sys 00038 import unittest 00039 import rospy 00040 import time 00041 import numpy 00042 00043 from pr2_calibration_estimation.camera import RectifiedCamera 00044 from numpy import * 00045 00046 def DefaultParams(): 00047 return {'baseline_shift':0, 00048 'f_shift':0, 00049 'cx_shift':0, 00050 'cy_shift':0, 00051 'cov': {'u':0.5, 'v':0.5} } 00052 00053 class TestRectifiedCamera(unittest.TestCase): 00054 00055 def test_project_easy_1(self): 00056 cam = RectifiedCamera(DefaultParams()) 00057 P_list = [ 1, 0, 0, 0, \ 00058 0, 1, 0, 0, \ 00059 0, 0, 1, 0 ] 00060 00061 pts = matrix( [ [ 0, 1, 0, 2 ], 00062 [ 0, 1, 1, 0 ], 00063 [ 1, 1, 2, 2 ], 00064 [ 1, 1, 1, 1 ]], float ) 00065 00066 expected = matrix( [ [ 0, 1, 0, 1], 00067 [ 0, 1, .5, 0] ] ) 00068 00069 result = cam.project(P_list, pts) 00070 00071 print "" 00072 print result 00073 00074 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6) 00075 00076 def test_project_easy_2(self): 00077 cam = RectifiedCamera(DefaultParams()) 00078 P_list = [ 1, 0, 0,-1, \ 00079 0, 1, 0, 0, \ 00080 0, 0, 1, 0 ] 00081 00082 pts = matrix( [ [ 0, 1, 0, 2 ], 00083 [ 0, 1, 1, 0 ], 00084 [ 1, 1, 2, 2 ], 00085 [ 1, 1, 1, 1 ]], float ) 00086 00087 expected = matrix( [ [-1, 0,-.5,.5], 00088 [ 0, 1, .5, 0] ] ) 00089 00090 result = cam.project(P_list, pts) 00091 00092 print "" 00093 print result 00094 00095 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6) 00096 00097 def test_project_easy_3(self): 00098 cam = RectifiedCamera(DefaultParams()) 00099 P_list = [ 1, 0, 0, 0, \ 00100 0, 1, 0, 0, \ 00101 0, 0, 1, 0 ] 00102 00103 cam.inflate(matrix([-1])) 00104 00105 pts = matrix( [ [ 0, 1, 0, 2 ], 00106 [ 0, 1, 1, 0 ], 00107 [ 1, 1, 2, 2 ], 00108 [ 1, 1, 1, 1 ]], float ) 00109 00110 expected = matrix( [ [-1, 0,-.5,.5], 00111 [ 0, 1, .5, 0] ] ) 00112 00113 result = cam.project(P_list, pts) 00114 00115 print "" 00116 print result 00117 00118 self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6) 00119 00120 00121 def test_free(self): 00122 cam = RectifiedCamera(DefaultParams()) 00123 free_list = cam.calc_free( {"baseline_shift":0, "f_shift":0, "cx_shift":0, "cy_shift":0} ) 00124 self.assertEqual(free_list[0], False) 00125 00126 free_list = cam.calc_free( {"baseline_shift":1, "f_shift":0, "cx_shift":0, "cy_shift":0} ) 00127 self.assertEqual(free_list[0], True) 00128 00129 self.assertEqual(len(free_list), 4) 00130 00131 def test_params_to_config(self): 00132 cam = RectifiedCamera(DefaultParams()) 00133 p = matrix([1, 0, 0, 0], float).T 00134 config = cam.params_to_config(p) 00135 self.assertAlmostEqual(config["baseline_shift"], 1, 6) 00136 00137 def test_length(self): 00138 cam = RectifiedCamera(DefaultParams()) 00139 self.assertEqual(cam.get_length(), 4) 00140 00141 def test_deflate(self): 00142 params = DefaultParams() 00143 params['baseline_shift'] = 10 00144 cam = RectifiedCamera(params) 00145 self.assertEqual(cam.deflate()[0,0], 10) 00146 00147 if __name__ == '__main__': 00148 import rostest 00149 rostest.unitrun('pr2_calibration_estimation', 'test_RectifiedCamera', TestRectifiedCamera, coverage_packages=['pr2_calibration_estimation.camera']) 00150