00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
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
00069 def deflate(self):
00070 return matrix([self._config[x] for x in param_names]).T
00071
00072
00073 def get_length(self):
00074 return len(param_names)
00075
00076 def get_param_names(self):
00077 return param_names;
00078
00079
00080
00081
00082
00083 def project(self, P_list, pts):
00084 N = pts.shape[1]
00085
00086
00087 P = reshape( matrix(P_list, float), (3,4) )
00088
00089
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
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
00102 pixel_pts_h = P * pts
00103
00104
00105
00106
00107
00108
00109
00110 pixel_pts = pixel_pts_h[0:2,:] / pixel_pts_h[2,:]
00111
00112 return pixel_pts
00113