camera_unittest.py
Go to the documentation of this file.
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('calibration_estimation')
00036 
00037 import sys
00038 import unittest
00039 import rospy
00040 import time
00041 import numpy
00042 
00043 from calibration_estimation.camera import RectifiedCamera
00044 from numpy import *
00045 
00046 def DefaultParams():
00047     return {'baseline_shift':0,
00048             'frame_id': 'default_frame',
00049             'chain_id': 'default_chain',
00050             'f_shift':0,
00051             'cx_shift':0,
00052             'cy_shift':0,
00053             'cov': {'u':0.5, 'v':0.5} }
00054 
00055 class TestRectifiedCamera(unittest.TestCase):
00056 
00057     def test_project_easy_1(self):
00058         cam = RectifiedCamera(DefaultParams())
00059         P_list = [ 1, 0, 0, 0, \
00060                    0, 1, 0, 0, \
00061                    0, 0, 1, 0 ]
00062 
00063         pts = matrix( [ [ 0, 1, 0, 2 ],
00064                         [ 0, 1, 1, 0 ],
00065                         [ 1, 1, 2, 2 ],
00066                         [ 1, 1, 1, 1 ]], float )
00067 
00068         expected = matrix( [ [ 0, 1,  0, 1],
00069                              [ 0, 1, .5, 0] ] )
00070 
00071         result = cam.project(P_list, pts)
00072 
00073         print ""
00074         print result
00075 
00076         self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
00077 
00078     def test_project_easy_2(self):
00079         cam = RectifiedCamera(DefaultParams())
00080         P_list = [ 1, 0, 0,-1, \
00081                    0, 1, 0, 0, \
00082                    0, 0, 1, 0 ]
00083 
00084         pts = matrix( [ [ 0, 1, 0, 2 ],
00085                         [ 0, 1, 1, 0 ],
00086                         [ 1, 1, 2, 2 ],
00087                         [ 1, 1, 1, 1 ]], float )
00088 
00089         expected = matrix( [ [-1, 0,-.5,.5],
00090                              [ 0, 1, .5, 0] ] )
00091 
00092         result = cam.project(P_list, pts)
00093 
00094         print ""
00095         print result
00096 
00097         self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
00098 
00099     def test_project_easy_3(self):
00100         cam = RectifiedCamera(DefaultParams())
00101         P_list = [ 1, 0, 0, 0, \
00102                    0, 1, 0, 0, \
00103                    0, 0, 1, 0 ]
00104 
00105         cam.inflate(matrix([-1]))
00106 
00107         pts = matrix( [ [ 0, 1, 0, 2 ],
00108                         [ 0, 1, 1, 0 ],
00109                         [ 1, 1, 2, 2 ],
00110                         [ 1, 1, 1, 1 ]], float )
00111 
00112         expected = matrix( [ [-1, 0,-.5,.5],
00113                              [ 0, 1, .5, 0] ] )
00114 
00115         result = cam.project(P_list, pts)
00116 
00117         print ""
00118         print result
00119 
00120         self.assertAlmostEqual(numpy.linalg.norm(result-expected), 0.0, 6)
00121 
00122 
00123     def test_free(self):
00124         cam = RectifiedCamera(DefaultParams())
00125         free_list = cam.calc_free( {"baseline_shift":0, "f_shift":0, "cx_shift":0, "cy_shift":0} )
00126         self.assertEqual(free_list[0], False)
00127 
00128         free_list = cam.calc_free( {"baseline_shift":1, "f_shift":0, "cx_shift":0, "cy_shift":0} )
00129         self.assertEqual(free_list[0], True)
00130 
00131         self.assertEqual(len(free_list), 4)
00132 
00133     def test_params_to_config(self):
00134         cam = RectifiedCamera(DefaultParams())
00135         p = matrix([1, 0, 0, 0], float).T
00136         config = cam.params_to_config(p)
00137         self.assertAlmostEqual(config["baseline_shift"], 1, 6)
00138 
00139     def test_length(self):
00140         cam = RectifiedCamera(DefaultParams())
00141         self.assertEqual(cam.get_length(), 4)
00142 
00143     def test_deflate(self):
00144         params = DefaultParams()
00145         params['baseline_shift'] = 10
00146         cam = RectifiedCamera(params)
00147         self.assertEqual(cam.deflate()[0,0], 10)
00148 
00149 if __name__ == '__main__':
00150     import rostest
00151     rostest.unitrun('calibration_estimation', 'test_RectifiedCamera', TestRectifiedCamera, coverage_packages=['calibration_estimation.camera'])
00152 


calibration_estimation
Author(s): Vijay Pradeep, Michael Ferguson
autogenerated on Tue Sep 27 2016 04:06:33