$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 import numpy 00034 from numpy import matrix, array, vsplit, sin, cos, reshape, ones 00035 import rospy 00036 00037 00038 param_names = ['baseline_shift', 'f_shift', 'cx_shift', 'cy_shift'] 00039 00040 class RectifiedCamera: 00041 ''' 00042 Primitive for projecting 3D points into a monocular camera. The baseline 00043 term of the projection matrix can be changed. The baseline shift is added 00044 to the P[0,3] term of the projection matrix found in CameraInfo 00045 Parameters are ordered as follows [baseline_shift, f_shift, cx_shift, cy_shift] 00046 ''' 00047 def __init__(self, config): 00048 rospy.logdebug("Initializng rectified camera") 00049 self._config = config 00050 self._cov_dict = config['cov'] 00051 00052 def calc_free(self, free_config): 00053 return [free_config[x] == 1 for x in param_names] 00054 00055 def params_to_config(self, param_vec): 00056 assert(param_vec.shape == (self.get_length(),1)) 00057 param_list = array(param_vec)[:,0].tolist() 00058 param_dict = dict(zip(param_names, param_list)) 00059 param_dict['cov'] = self._cov_dict 00060 return param_dict 00061 00062 # Convert column vector of params into config, expects a 4x1 matrix 00063 def inflate(self, param_vec): 00064 param_list = array(param_vec)[:,0].tolist() 00065 for x,y in zip(param_names, param_list): 00066 self._config[x] = y 00067 00068 # Return column vector of config. In this case, it's always a 4x1 matrix 00069 def deflate(self): 00070 return matrix([self._config[x] for x in param_names]).T 00071 00072 # Returns # of params needed for inflation & deflation 00073 def get_length(self): 00074 return len(param_names) 00075 00076 def get_param_names(self): 00077 return param_names; 00078 00079 # Project a set of 3D points points into pixel coordinates 00080 # P_list - Projection matrix. We expect this to be a 1x12 list. We then reshape 00081 # it into a 3x4 matrix (by filling 1 row at a time) 00082 # pts - 4xN numpy matrix holding the points that we want to project (homogenous coords) 00083 def project(self, P_list, pts): 00084 N = pts.shape[1] 00085 00086 # Reshape P_list into an actual matrix 00087 P = reshape( matrix(P_list, float), (3,4) ) 00088 00089 # Update the baseline by the "baseline_shift" 00090 P[0,3] = P[0,3] + self._config['baseline_shift'] 00091 P[0,0] = P[0,0] + self._config['f_shift'] 00092 P[1,1] = P[1,1] + self._config['f_shift'] 00093 P[0,2] = P[0,2] + self._config['cx_shift'] 00094 P[1,2] = P[1,2] + self._config['cy_shift'] 00095 00096 #import code; code.interact(local=locals()) 00097 if (pts.shape[0] == 3): 00098 rospy.logfatal("Got vector of points with only 3 rows. Was expecting at 4 rows (homogenous coordinates)") 00099 00100 00101 # Apply projection matrix 00102 pixel_pts_h = P * pts 00103 00104 # print "pixel_points_h" 00105 # print pixel_pts_h 00106 00107 #import code; code.interact(local=locals()) 00108 00109 # Strip out last row (3rd) and rescale 00110 pixel_pts = pixel_pts_h[0:2,:] / pixel_pts_h[2,:] 00111 00112 return pixel_pts 00113