34 from numpy
import matrix, array, vsplit, sin, cos, reshape, ones, sqrt
37 param_names = [
'baseline_shift',
'f_shift',
'cx_shift',
'cy_shift']
41 Primitive for projecting 3D points into a monocular camera. The baseline 42 term of the projection matrix can be changed. The baseline shift is added 43 to the P[0,3] term of the projection matrix found in CameraInfo 44 Parameters are ordered as follows [baseline_shift, f_shift, cx_shift, cy_shift] 47 rospy.logdebug(
'Initializing rectified camera')
51 self.
_rgbd = config[
"baseline_rgbd"] != 0.0
56 return [free_config[x] == 1
for x
in param_names]
59 param_list = array(param_vec)[:,0].tolist()
60 param_dict = dict(zip(param_names, param_list))
63 param_dict[
'baseline_rgbd'] = self.
_rgbd 64 param_dict[
'frame_id'] = self.
_config[
'frame_id']
65 param_dict[
'chain_id'] = self.
_config[
'chain_id']
70 param_list = array(param_vec)[:,0].tolist()
71 for x,y
in zip(param_names, param_list):
76 return matrix([self.
_config[x]
for x
in param_names]).T
80 return len(param_names)
93 P = reshape( matrix(P_list, float), (3,4) )
96 P[0,3] = P[0,3] + self.
_config[
'baseline_shift']
97 P[0,0] = P[0,0] + self.
_config[
'f_shift']
98 P[1,1] = P[1,1] + self.
_config[
'f_shift']
99 P[0,2] = P[0,2] + self.
_config[
'cx_shift']
100 P[1,2] = P[1,2] + self.
_config[
'cy_shift']
102 if (pts.shape[0] == 3):
103 rospy.logfatal(
'Got vector of points with only 3 rows. Was expecting at 4 rows (homogenous coordinates)')
106 pixel_pts_h = P * pts
110 pixel_pts = pixel_pts_h[0:3,:] / pixel_pts_h[2,:]
115 pixel_pts = pixel_pts_h[0:2,:] / pixel_pts_h[2,:]
120 P = reshape( matrix(P_list, float), (3,4) )
121 return (P[0,0] * self.
_config[
"baseline_rgbd"]) / depth
def __init__(self, config)
def project(self, P_list, pts)
def get_param_names(self)
def get_disparity(self, P_list, depth)
def calc_free(self, free_config)
def inflate(self, param_vec)
def params_to_config(self, param_vec)