def __init__(self, mesh, T_mesh_world, mat_props=MaterialProperties()): self.mesh = mesh self.T_mesh_world = T_mesh_world self.mat_props = mat_props
def images(self, mesh, object_to_camera_poses, mat_props=None, light_props=None, enable_lighting=True, debug=False): """Render images of the given mesh at the list of object to camera poses. Parameters ---------- mesh : :obj:`Mesh3D` The mesh to be rendered. object_to_camera_poses : :obj:`list` of :obj:`RigidTransform` A list of object to camera transforms to render from. mat_props : :obj:`MaterialProperties` Material properties for the mesh light_props : :obj:`MaterialProperties` Lighting properties for the scene enable_lighting : bool Whether or not to enable lighting debug : bool Whether or not to debug the C++ meshrendering code. Returns ------- :obj:`tuple` of `numpy.ndarray` A 2-tuple of ndarrays. The first, which represents the color image, contains ints (0 to 255) and is of shape (height, width, 3). Each pixel is a 3-ndarray (red, green, blue) associated with a given y and x value. The second, which represents the depth image, contains floats and is of shape (height, width). Each pixel is a single float that represents the depth of the image. """ # get mesh spec as numpy arrays vertex_arr = mesh.vertices tri_arr = mesh.triangles.astype(np.int32) if mesh.normals is None: mesh.compute_vertex_normals() norms_arr = mesh.normals # set default material properties if mat_props is None: mat_props = MaterialProperties() mat_props_arr = mat_props.arr # set default light properties if light_props is None: light_props = LightingProperties() # render for each object to camera pose # TODO: clean up interface, use modelview matrix!!!! color_ims = [] depth_ims = [] render_start = time.time() for T_obj_camera in object_to_camera_poses: # form projection matrix R = T_obj_camera.rotation t = T_obj_camera.translation P = self._camera_intr.proj_matrix.dot(np.c_[R, t]) # form light props light_props.set_pose(T_obj_camera) light_props_arr = light_props.arr # render images for each c, d = meshrender.render_mesh([P], self._camera_intr.height, self._camera_intr.width, vertex_arr, tri_arr, norms_arr, mat_props_arr, light_props_arr, enable_lighting, debug) color_ims.extend(c) depth_ims.extend(d) render_stop = time.time() logging.debug('Rendering took %.3f sec' %(render_stop - render_start)) return color_ims, depth_ims
vis3d.figure() vis3d.mesh(mesh) vis3d.normals(NormalCloud(mesh.normals.T), PointCloud(mesh.vertices.T), subsample=10) vis3d.show() d = utils.sqrt_ceil(len(stable_poses)) vis.figure(size=(16, 16)) table_mesh = ObjFile('data/meshes/table.obj').read() table_mesh = table_mesh.subdivide() table_mesh.compute_vertex_normals() table_mat_props = MaterialProperties(color=(0, 255, 0), ambient=0.5, diffuse=1.0, specular=1, shininess=0) for k, stable_pose in enumerate(stable_poses): logging.info('Rendering stable pose %d' % (k)) # set resting pose T_obj_world = mesh.get_T_surface_obj( stable_pose.T_obj_table).as_frames('obj', 'world') # load camera intrinsics camera_intr = CameraIntrinsics.load( 'data/camera_intr/primesense_carmine_108.intr') #camera_intr = camera_intr.resize(4)