$search
00001 #!/usr/bin/env python 00002 ################################################################# 00003 ##\file 00004 # 00005 # \note 00006 # Copyright (c) 2011-2012 \n 00007 # Fraunhofer Institute for Manufacturing Engineering 00008 # and Automation (IPA) \n\n 00009 # 00010 ################################################################# 00011 # 00012 # \note 00013 # Project name: care-o-bot 00014 # \note 00015 # ROS stack name: cob_calibration 00016 # \note 00017 # ROS package name: cob_camera_calibration 00018 # 00019 # \author 00020 # Author: Sebastian Haug, email:sebhaug@gmail.com 00021 # \author 00022 # Supervised by: Florian Weisshardt, email:florian.weisshardt@ipa.fhg.de 00023 # 00024 # \date Date of creation: November 2011 00025 # 00026 ################################################################# 00027 # 00028 # Redistribution and use in source and binary forms, with or without 00029 # modification, are permitted provided that the following conditions are met: 00030 # 00031 # - Redistributions of source code must retain the above copyright 00032 # notice, this list of conditions and the following disclaimer. \n 00033 # - Redistributions in binary form must reproduce the above copyright 00034 # notice, this list of conditions and the following disclaimer in the 00035 # documentation and/or other materials provided with the distribution. \n 00036 # - Neither the name of the Fraunhofer Institute for Manufacturing 00037 # Engineering and Automation (IPA) nor the names of its 00038 # contributors may be used to endorse or promote products derived from 00039 # this software without specific prior written permission. \n 00040 # 00041 # This program is free software: you can redistribute it and/or modify 00042 # it under the terms of the GNU Lesser General Public License LGPL as 00043 # published by the Free Software Foundation, either version 3 of the 00044 # License, or (at your option) any later version. 00045 # 00046 # This program is distributed in the hope that it will be useful, 00047 # but WITHOUT ANY WARRANTY; without even the implied warranty of 00048 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00049 # GNU Lesser General Public License LGPL for more details. 00050 # 00051 # You should have received a copy of the GNU Lesser General Public 00052 # License LGPL along with this program. 00053 # If not, see <http://www.gnu.org/licenses/>. 00054 # 00055 ################################################################# 00056 PKG = 'cob_camera_calibration' 00057 import roslib; roslib.load_manifest(PKG) 00058 import unittest 00059 00060 import numpy as np 00061 import cv2 00062 import yaml 00063 00064 from cob_camera_calibration import CheckerboardDetector, Checkerboard 00065 00066 CHECKERBOARD_IMAGE="test/data/cb1.jpg" 00067 CHECKERBOARD_IMAGE_EXPECTED_POINTS_YAML = "test/data/cb1_points.yaml" 00068 00069 class TestCalibrationObjectDetector(unittest.TestCase): 00070 def test_detect_image_points_gray_image(self): 00071 # create Checkerboard instance and read image 00072 c = Checkerboard((9, 6), 0.03) 00073 image = cv2.imread(CHECKERBOARD_IMAGE, 1) 00074 00075 # create CheckerboardDetector instance and detect image points 00076 cd = CheckerboardDetector(c) 00077 points = cd.detect_image_points(image, False) 00078 00079 #dump = {'points': points.flatten().tolist()} 00080 #yaml.dump(dump, open(CHECKERBOARD_IMAGE_EXPECTED_POINTS_YAML, "w")) 00081 00082 # load expected points 00083 points_expected = yaml.load(file(CHECKERBOARD_IMAGE_EXPECTED_POINTS_YAML))['points'] 00084 self.assertTrue(np.allclose(points.flatten().tolist(), points_expected)) 00085 00086 def test_detect_image_points_color_image(self): 00087 # create Checkerboard instance and read image 00088 c = Checkerboard((9, 6), 0.03) 00089 image = cv2.imread(CHECKERBOARD_IMAGE, 0) 00090 00091 # create CheckerboardDetector instance and detect image points 00092 cd = CheckerboardDetector(c) 00093 points = cd.detect_image_points(image, True) 00094 00095 #dump = {'points': points.flatten().tolist()} 00096 #yaml.dump(dump, open(CHECKERBOARD_IMAGE_EXPECTED_POINTS_YAML, "w")) 00097 00098 # load expected points 00099 points_expected = yaml.load(file(CHECKERBOARD_IMAGE_EXPECTED_POINTS_YAML))['points'] 00100 self.assertTrue(np.allclose(points.flatten().tolist(), points_expected)) 00101 00102 def test_calculate_object_pose(self): 00103 # create Checkerboard instance and read image 00104 c = Checkerboard((9, 6), 0.03) 00105 image = cv2.imread(CHECKERBOARD_IMAGE, 0) 00106 00107 # create CheckerboardDetector instance and detect object pose 00108 # (only dummy matrices, does not correspond to real camera used) 00109 cd = CheckerboardDetector(c) 00110 camera_matrix = np.matrix([1200, 0, 600, 0, 1200, 600, 0, 0, 1], dtype=np.float32).reshape((3,3)) 00111 dist_coeffs = np.matrix([0, 0, 0, 0, 0], dtype=np.float32).reshape((1,5)) 00112 (rvec, tvec) = cd.calculate_object_pose(image, camera_matrix, dist_coeffs, True) 00113 00114 rvec_expected = np.matrix([[0.99905897, 0.035207, -0.02533079], 00115 [-0.0208742, 0.90224111, 0.43072642], 00116 [ 0.03801906, -0.42979234, 0.90212699]]) 00117 tvec_expected = np.matrix([[-0.03181351], [-0.13593217], [ 0.7021291]]) 00118 00119 self.assertTrue(np.allclose(rvec_expected, rvec)) 00120 self.assertTrue(np.allclose(tvec_expected, tvec)) 00121 00122 if __name__ == '__main__': 00123 import rostest 00124 rostest.rosrun(PKG, 'TestCalibrationObjectDetector', TestCalibrationObjectDetector)