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, sqrt
00035 import rospy
00036
00037 param_names = ['baseline_shift', 'f_shift', 'cx_shift', 'cy_shift']
00038
00039 class RectifiedCamera:
00040 '''
00041 Primitive for projecting 3D points into a monocular camera. The baseline
00042 term of the projection matrix can be changed. The baseline shift is added
00043 to the P[0,3] term of the projection matrix found in CameraInfo
00044 Parameters are ordered as follows [baseline_shift, f_shift, cx_shift, cy_shift]
00045 '''
00046 def __init__(self, config):
00047 rospy.logdebug('Initializing rectified camera')
00048 self._config = config
00049 self._cov_dict = config['cov']
00050 try:
00051 self._rgbd = config["baseline_rgbd"] != 0.0
00052 except:
00053 self._rgbd = None
00054
00055 def calc_free(self, free_config):
00056 return [free_config[x] == 1 for x in param_names]
00057
00058 def params_to_config(self, param_vec):
00059 param_list = array(param_vec)[:,0].tolist()
00060 param_dict = dict(zip(param_names, param_list))
00061 param_dict['cov'] = self._cov_dict
00062 if self._rgbd:
00063 param_dict['baseline_rgbd'] = self._rgbd
00064 param_dict['frame_id'] = self._config['frame_id']
00065 param_dict['chain_id'] = self._config['chain_id']
00066 return param_dict
00067
00068
00069 def inflate(self, param_vec):
00070 param_list = array(param_vec)[:,0].tolist()
00071 for x,y in zip(param_names, param_list):
00072 self._config[x] = y
00073
00074
00075 def deflate(self):
00076 return matrix([self._config[x] for x in param_names]).T
00077
00078
00079 def get_length(self):
00080 return len(param_names)
00081
00082 def get_param_names(self):
00083 return param_names
00084
00085
00086
00087
00088
00089 def project(self, P_list, pts):
00090 N = pts.shape[1]
00091
00092
00093 P = reshape( matrix(P_list, float), (3,4) )
00094
00095
00096 P[0,3] = P[0,3] + self._config['baseline_shift']
00097 P[0,0] = P[0,0] + self._config['f_shift']
00098 P[1,1] = P[1,1] + self._config['f_shift']
00099 P[0,2] = P[0,2] + self._config['cx_shift']
00100 P[1,2] = P[1,2] + self._config['cy_shift']
00101
00102 if (pts.shape[0] == 3):
00103 rospy.logfatal('Got vector of points with only 3 rows. Was expecting at 4 rows (homogenous coordinates)')
00104
00105
00106 pixel_pts_h = P * pts
00107
00108
00109 if self._rgbd:
00110 pixel_pts = pixel_pts_h[0:3,:] / pixel_pts_h[2,:]
00111 for i in range(N):
00112 depth = pts[2,i]
00113 pixel_pts[2,i] = self.get_disparity(P,depth)
00114 else:
00115 pixel_pts = pixel_pts_h[0:2,:] / pixel_pts_h[2,:]
00116
00117 return pixel_pts
00118
00119 def get_disparity(self, P_list, depth):
00120 P = reshape( matrix(P_list, float), (3,4) )
00121 return (P[0,0] * self._config["baseline_rgbd"]) / depth
00122
00123