def render_data(self): logging.basicConfig(level=logging.WARNING) for dataset in self.datasets: logging.info('Generating data for dataset %s' % dataset.name) object_keys = dataset.object_keys for obj_key in object_keys: self.tensor_datapoint['obj_labels'] = self.cur_obj_label if self.cur_obj_label % 10 == 0: logging.info("Object number: %d" % self.cur_obj_label) self.obj = dataset[obj_key] grasps = dataset.grasps(self.obj.key, gripper=self.gripper.name) # Load grasp metrics grasp_metrics = dataset.grasp_metrics(self.obj.key, grasps, gripper=self.gripper.name) # setup collision checker collision_checker = GraspCollisionChecker(self.gripper) collision_checker.set_graspable_object(self.obj) # read in the stable poses of the mesh stable_poses = dataset.stable_poses(self.obj.key) # Iterate through stable poses for i, stable_pose in enumerate(stable_poses): if not stable_pose.p > self._stable_pose_min_p: continue self.tensor_datapoint['pose_labels'] = self.cur_pose_label # setup table in collision checker T_obj_stp = stable_pose.T_obj_table.as_frames('obj', 'stp') T_obj_table = self.obj.mesh.get_T_surface_obj(T_obj_stp, delta=self._table_offset).as_frames('obj', 'table') T_table_obj = T_obj_table.inverse() T_obj_stp = self.obj.mesh.get_T_surface_obj(T_obj_stp) collision_checker.set_table(self._table_mesh_filename, T_table_obj) # sample images from random variable T_table_obj = RigidTransform(from_frame='table', to_frame='obj') scene_objs = {'table': SceneObject(self.table_mesh, T_table_obj)} # Set up image renderer samples = self.render_images(scene_objs, stable_pose, self.config['images_per_stable_pose'], camera_config=self._camera_configs()) for sample in samples: self.save_samples(sample, grasps, T_obj_stp, collision_checker, grasp_metrics, stable_pose) self.cur_pose_label += 1 gc.collect() # next stable pose self.cur_obj_label += 1 # next object # Save dataset self.tensor_dataset.flush()
def start_rendering(self): self._load_file_ids() for object_id in self.all_objects: self._load_data(object_id) for i, stable_pose in enumerate(self.stable_poses): try: candidate_grasp_info = self.candidate_grasps_dict[ stable_pose.id] except KeyError: continue if not candidate_grasp_info: Warning("Candidate grasp info of object id %s empty" % object_id) Warning("Continue.") continue T_obj_stp = stable_pose.T_obj_table.as_frames('obj', 'stp') T_obj_stp = self.object_mesh.get_T_surface_obj(T_obj_stp) T_table_obj = RigidTransform(from_frame='table', to_frame='obj') scene_objs = { 'table': SceneObject(self.table_mesh, T_table_obj) } urv = UniformPlanarWorksurfaceImageRandomVariable( self.object_mesh, [RenderMode.DEPTH_SCENE, RenderMode.SEGMASK], 'camera', self.config['env_rv_params'], scene_objs=scene_objs, stable_pose=stable_pose) render_sample = urv.rvs(size=self.random_positions) # for render_sample in render_samples: binary_im = render_sample.renders[RenderMode.SEGMASK].image depth_im = render_sample.renders[ RenderMode.DEPTH_SCENE].image.crop(300, 300) orig_im = Image.fromarray(self._scale_image(depth_im.data)) if self.show_images: orig_im.show() orig_im.convert('RGB').save(self.output_dir + '/images/' + object_id + '_elev_' + str(self.elev) + '_original.png') print("Saved original") T_stp_camera = render_sample.camera.object_to_camera_pose shifted_camera_intr = render_sample.camera.camera_intr.crop( 300, 300, 240, 320) depth_points = self._reproject_to_3D(depth_im, shifted_camera_intr) transformed_points, T_camera = self._transformation( depth_points) camera_dir = np.dot(T_camera.rotation, np.array([0.0, 0.0, -1.0])) pcd = o3d.geometry.PointCloud() # print(camera_dir) pcd.points = o3d.utility.Vector3dVector(transformed_points.T) # TODO check normals!! # pcd.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30)) # pcd.normals = o3d.utility.Vector3dVector(-np.asarray(pcd.normals)) normals = np.repeat([camera_dir], len(transformed_points.T), axis=0) pcd.normals = o3d.utility.Vector3dVector(normals) # cs_points = [[0, 0, 0], [1, 0, 0], [0, 1, 0], [0, 0, 1]] # cs_lines = [[0, 1], [0, 2], [0, 3]] # colors = [[1, 0, 0], [0, 1, 0], [0, 0, 1]] # cs = o3d.geometry.LineSet(points=o3d.utility.Vector3dVector(cs_points), # lines=o3d.utility.Vector2iVector(cs_lines)) # cs.colors = o3d.utility.Vector3dVector(colors) # o3d.visualization.draw_geometries([pcd]) depth = self._o3d_meshing(pcd) # projected_depth_im,new_camera_intr,table_height = self._projection(new_points,shifted_camera_intr) new_camera_intr = shifted_camera_intr new_camera_intr.cx = 150 new_camera_intr.cy = 150 projected_depth_im = np.asarray(depth) projected_depth_im[projected_depth_im == 0.0] = -1.0 table_height = np.median( projected_depth_im[projected_depth_im != -1.0].flatten()) print("Minimum depth:", min(projected_depth_im.flatten())) print("Maximum depth:", max(projected_depth_im.flatten())) im = Image.fromarray(self._scale_image(projected_depth_im)) projected_depth_im = DepthImage(projected_depth_im, frame='new_camera') cx = projected_depth_im.center[1] cy = projected_depth_im.center[0] # Grasp conversion T_obj_old_camera = T_stp_camera * T_obj_stp.as_frames( 'obj', T_stp_camera.from_frame) T_obj_camera = T_camera.dot(T_obj_old_camera) for grasp_info in candidate_grasp_info: grasp = grasp_info.grasp collision_free = grasp_info.collision_free grasp_2d = grasp.project_camera(T_obj_camera, new_camera_intr) dx = cx - grasp_2d.center.x dy = cy - grasp_2d.center.y translation = np.array([dy, dx]) # Project 3D old_camera_cs contact points into new camera cs contact_points = np.append(grasp_info.contact_point1, 1).T new_cam = np.dot(T_obj_camera.matrix, contact_points) c1 = new_camera_intr.project( Point(new_cam[0:3], frame=new_camera_intr.frame)) contact_points = np.append(grasp_info.contact_point2, 1).T new_cam = np.dot(T_obj_camera.matrix, contact_points) c2 = new_camera_intr.project( Point(new_cam[0:3], frame=new_camera_intr.frame)) # Check if there are occlusions at contact points if projected_depth_im.data[ c1.x, c1.y] == -1.0 or projected_depth_im.data[ c2.x, c2.y] == -1.0: print("Contact point at occlusion") contact_occlusion = True else: contact_occlusion = False # Mark contact points in image im = im.convert('RGB') if False: im_draw = ImageDraw.Draw(im) im_draw.line([(c1[0], c1[1] - 10), (c1[0], c1[1] + 10)], fill=(255, 0, 0, 255)) im_draw.line([(c1[0] - 10, c1[1]), (c1[0] + 10, c1[1])], fill=(255, 0, 0, 255)) im_draw.line([(c2[0], c2[1] - 10), (c2[0], c2[1] + 10)], fill=(255, 0, 0, 255)) im_draw.line([(c2[0] - 10, c2[1]), (c2[0] + 10, c2[1])], fill=(255, 0, 0, 255)) if self.show_images: im.show() im.save(self.output_dir + '/images/' + object_id + '_elev_' + str(self.elev) + '_reprojected.png') # Transform and crop image depth_im_tf = projected_depth_im.transform( translation, grasp_2d.angle) depth_im_tf = depth_im_tf.crop(96, 96) # Apply transformation to contact points trans_map = np.array([[1, 0, dx], [0, 1, dy]]) rot_map = cv2.getRotationMatrix2D( (cx, cy), np.rad2deg(grasp_2d.angle), 1) trans_map_aff = np.r_[trans_map, [[0, 0, 1]]] rot_map_aff = np.r_[rot_map, [[0, 0, 1]]] full_map = rot_map_aff.dot(trans_map_aff) # print("Full map",full_map) c1_rotated = (np.dot(full_map, np.r_[c1.vector, [1]]) - np.array([150 - 48, 150 - 48, 0])) / 3 c2_rotated = (np.dot(full_map, np.r_[c2.vector, [1]]) - np.array([150 - 48, 150 - 48, 0])) / 3 grasp_line = depth_im_tf.data[48] occlusions = len(np.where(np.squeeze(grasp_line) == -1)[0]) # Set occlusions to table height for resizing image depth_im_tf.data[depth_im_tf.data == -1.0] = table_height depth_image = Image.fromarray(np.asarray(depth_im_tf.data))\ .resize((32, 32), resample=Image.BILINEAR) depth_im_tf_table = np.asarray(depth_image).reshape( 32, 32, 1) # depth_im_tf_table = depth_im_tf.resize((32, 32,), interp='bilinear') im = Image.fromarray( self._scale_image(depth_im_tf_table.reshape( 32, 32))).convert('RGB') draw = ImageDraw.Draw(im) draw.line([(c1_rotated[0], c1_rotated[1] - 3), (c1_rotated[0], c1_rotated[1] + 3)], fill=(255, 0, 0, 255)) draw.line([(c1_rotated[0] - 3, c1_rotated[1]), (c1_rotated[0] + 3, c1_rotated[1])], fill=(255, 0, 0, 255)) draw.line([(c2_rotated[0], c2_rotated[1] - 3), (c2_rotated[0], c2_rotated[1] + 3)], fill=(255, 0, 0, 255)) draw.line([(c2_rotated[0] - 3, c2_rotated[1]), (c2_rotated[0] + 3, c2_rotated[1])], fill=(255, 0, 0, 255)) if self.show_images: im.show() im.save(self.output_dir + '/images/' + object_id + '_elev_' + str(self.elev) + '_transformed.png') hand_pose = np.r_[grasp_2d.center.y, grasp_2d.center.x, grasp_2d.depth, grasp_2d.angle, grasp_2d.center.y - new_camera_intr.cy, grasp_2d.center.x - new_camera_intr.cx, grasp_2d.width_px / 3] self.tensor_datapoint[ 'depth_ims_tf_table'] = depth_im_tf_table self.tensor_datapoint['hand_poses'] = hand_pose self.tensor_datapoint['obj_labels'] = self.cur_obj_label self.tensor_datapoint['collision_free'] = collision_free self.tensor_datapoint['pose_labels'] = self.cur_pose_label self.tensor_datapoint[ 'image_labels'] = self.cur_image_label self.tensor_datapoint['files'] = [self.tensor, self.array] self.tensor_datapoint['occlusions'] = occlusions self.tensor_datapoint[ 'contact_occlusion'] = contact_occlusion for metric_name, metric_val in self.grasp_metrics[str( grasp.id)].iteritems(): coll_free_metric = (1 * collision_free) * metric_val self.tensor_datapoint[metric_name] = coll_free_metric self.tensor_dataset.add(self.tensor_datapoint) print("Saved dataset point") self.cur_image_label += 1 self.cur_pose_label += 1 gc.collect() self.cur_obj_label += 1 self.tensor_dataset.flush()
def generate_gqcnn_dataset(dataset_path, database, target_object_keys, env_rv_params, gripper_name, config): """ Generates a GQ-CNN TensorDataset for training models with new grippers, quality metrics, objects, and cameras. Parameters ---------- dataset_path : str path to save the dataset to database : :obj:`Hdf5Database` Dex-Net database containing the 3D meshes, grasps, and grasp metrics target_object_keys : :obj:`OrderedDict` dictionary mapping dataset names to target objects (either 'all' or a list of specific object keys) env_rv_params : :obj:`OrderedDict` parameters of the camera and object random variables used in sampling (see meshpy.UniformPlanarWorksurfaceImageRandomVariable for more info) gripper_name : str name of the gripper to use config : :obj:`autolab_core.YamlConfig` other parameters for dataset generation Notes ----- Required parameters of config are specified in Other Parameters Other Parameters ---------------- images_per_stable_pose : int number of object and camera poses to sample for each stable pose stable_pose_min_p : float minimum probability of occurrence for a stable pose to be used in data generation (used to prune bad stable poses gqcnn/crop_width : int width, in pixels, of crop region around each grasp center, before resize (changes the size of the region seen by the GQ-CNN) gqcnn/crop_height : int height, in pixels, of crop region around each grasp center, before resize (changes the size of the region seen by the GQ-CNN) gqcnn/final_width : int width, in pixels, of final transformed grasp image for input to the GQ-CNN (defaults to 32) gqcnn/final_height : int height, in pixels, of final transformed grasp image for input to the GQ-CNN (defaults to 32) table_alignment/max_approach_table_angle : float max angle between the grasp axis and the table normal when the grasp approach is maximally aligned with the table normal table_alignment/max_approach_offset : float max deviation from perpendicular approach direction to use in grasp collision checking table_alignment/num_approach_offset_samples : int number of approach samples to use in collision checking collision_checking/table_offset : float max allowable interpenetration between the gripper and table to be considered collision free collision_checking/table_mesh_filename : str path to a table mesh for collision checking (default data/meshes/table.obj) collision_checking/approach_dist : float distance, in meters, between the approach pose and final grasp pose along the grasp axis collision_checking/delta_approach : float amount, in meters, to discretize the straight-line path from the gripper approach pose to the final grasp pose tensors/datapoints_per_file : int number of datapoints to store in each unique tensor file on disk tensors/fields : :obj:`dict` dictionary mapping field names to dictionaries specifying the data type, height, width, and number of channels for each tensor debug : bool True (or 1) if the random seed should be set to enforce deterministic behavior, False (0) otherwise vis/candidate_grasps : bool True (or 1) if the collision free candidate grasps should be displayed in 3D (for debugging) vis/rendered_images : bool True (or 1) if the rendered images for each stable pose should be displayed (for debugging) vis/grasp_images : bool True (or 1) if the transformed grasp images should be displayed (for debugging) """ # read data gen params output_dir = dataset_path gripper = RobotGripper.load(gripper_name) image_samples_per_stable_pose = config['images_per_stable_pose'] stable_pose_min_p = config['stable_pose_min_p'] # read gqcnn params gqcnn_params = config['gqcnn'] im_crop_height = gqcnn_params['crop_height'] im_crop_width = gqcnn_params['crop_width'] im_final_height = gqcnn_params['final_height'] im_final_width = gqcnn_params['final_width'] cx_crop = float(im_crop_width) / 2 cy_crop = float(im_crop_height) / 2 # open database dataset_names = target_object_keys.keys() datasets = [database.dataset(dn) for dn in dataset_names] # set target objects for dataset in datasets: if target_object_keys[dataset.name] == 'all': target_object_keys[dataset.name] = dataset.object_keys # setup grasp params table_alignment_params = config['table_alignment'] min_grasp_approach_offset = -np.deg2rad( table_alignment_params['max_approach_offset']) max_grasp_approach_offset = np.deg2rad( table_alignment_params['max_approach_offset']) max_grasp_approach_table_angle = np.deg2rad( table_alignment_params['max_approach_table_angle']) num_grasp_approach_samples = table_alignment_params[ 'num_approach_offset_samples'] phi_offsets = [] if max_grasp_approach_offset == min_grasp_approach_offset: phi_inc = 1 elif num_grasp_approach_samples == 1: phi_inc = max_grasp_approach_offset - min_grasp_approach_offset + 1 else: phi_inc = (max_grasp_approach_offset - min_grasp_approach_offset) / ( num_grasp_approach_samples - 1) phi = min_grasp_approach_offset while phi <= max_grasp_approach_offset: phi_offsets.append(phi) phi += phi_inc # setup collision checking coll_check_params = config['collision_checking'] approach_dist = coll_check_params['approach_dist'] delta_approach = coll_check_params['delta_approach'] table_offset = coll_check_params['table_offset'] table_mesh_filename = coll_check_params['table_mesh_filename'] if not os.path.isabs(table_mesh_filename): table_mesh_filename = os.path.join( os.path.dirname(os.path.realpath(__file__)), '..', table_mesh_filename) table_mesh = ObjFile(table_mesh_filename).read() # set tensor dataset config tensor_config = config['tensors'] tensor_config['fields']['depth_ims_tf_table']['height'] = im_final_height tensor_config['fields']['depth_ims_tf_table']['width'] = im_final_width tensor_config['fields']['obj_masks']['height'] = im_final_height tensor_config['fields']['obj_masks']['width'] = im_final_width # add available metrics (assuming same are computed for all objects) metric_names = [] dataset = datasets[0] obj_keys = dataset.object_keys if len(obj_keys) == 0: raise ValueError('No valid objects in dataset %s' % (dataset.name)) obj = dataset[obj_keys[0]] grasps = dataset.grasps(obj.key, gripper=gripper.name) grasp_metrics = dataset.grasp_metrics(obj.key, grasps, gripper=gripper.name) metric_names = grasp_metrics[grasp_metrics.keys()[0]].keys() for metric_name in metric_names: tensor_config['fields'][metric_name] = {} tensor_config['fields'][metric_name]['dtype'] = 'float32' # init tensor dataset tensor_dataset = TensorDataset(output_dir, tensor_config) tensor_datapoint = tensor_dataset.datapoint_template # setup log file experiment_log_filename = os.path.join(output_dir, 'dataset_generation.log') formatter = logging.Formatter('%(asctime)s %(levelname)s: %(message)s') hdlr = logging.FileHandler(experiment_log_filename) hdlr.setFormatter(formatter) logging.getLogger().addHandler(hdlr) root_logger = logging.getLogger() # copy config out_config_filename = os.path.join(output_dir, 'dataset_generation.json') ordered_dict_config = collections.OrderedDict() for key in config.keys(): ordered_dict_config[key] = config[key] with open(out_config_filename, 'w') as outfile: json.dump(ordered_dict_config, outfile) # 1. Precompute the set of valid grasps for each stable pose: # i) Perpendicular to the table # ii) Collision-free along the approach direction # load grasps if they already exist grasp_cache_filename = os.path.join(output_dir, CACHE_FILENAME) if os.path.exists(grasp_cache_filename): logging.info('Loading grasp candidates from file') candidate_grasps_dict = pkl.load(open(grasp_cache_filename, 'rb')) # otherwise re-compute by reading from the database and enforcing constraints else: # create grasps dict candidate_grasps_dict = {} # loop through datasets and objects for dataset in datasets: logging.info('Reading dataset %s' % (dataset.name)) for obj in dataset: if obj.key not in target_object_keys[dataset.name]: continue # init candidate grasp storage candidate_grasps_dict[obj.key] = {} # setup collision checker collision_checker = GraspCollisionChecker(gripper) collision_checker.set_graspable_object(obj) # read in the stable poses of the mesh stable_poses = dataset.stable_poses(obj.key) for i, stable_pose in enumerate(stable_poses): # render images if stable pose is valid if stable_pose.p > stable_pose_min_p: candidate_grasps_dict[obj.key][stable_pose.id] = [] # setup table in collision checker T_obj_stp = stable_pose.T_obj_table.as_frames( 'obj', 'stp') T_obj_table = obj.mesh.get_T_surface_obj( T_obj_stp, delta=table_offset).as_frames('obj', 'table') T_table_obj = T_obj_table.inverse() collision_checker.set_table(table_mesh_filename, T_table_obj) # read grasp and metrics grasps = dataset.grasps(obj.key, gripper=gripper.name) logging.info( 'Aligning %d grasps for object %s in stable %s' % (len(grasps), obj.key, stable_pose.id)) # align grasps with the table aligned_grasps = [ grasp.perpendicular_table(stable_pose) for grasp in grasps ] # check grasp validity logging.info( 'Checking collisions for %d grasps for object %s in stable %s' % (len(grasps), obj.key, stable_pose.id)) for aligned_grasp in aligned_grasps: # check angle with table plane and skip unaligned grasps _, grasp_approach_table_angle, _ = aligned_grasp.grasp_angles_from_stp_z( stable_pose) perpendicular_table = ( np.abs(grasp_approach_table_angle) < max_grasp_approach_table_angle) if not perpendicular_table: continue # check whether any valid approach directions are collision free collision_free = False for phi_offset in phi_offsets: rotated_grasp = aligned_grasp.grasp_y_axis_offset( phi_offset) collides = collision_checker.collides_along_approach( rotated_grasp, approach_dist, delta_approach) if not collides: collision_free = True break # store if aligned to table candidate_grasps_dict[obj.key][ stable_pose.id].append( GraspInfo(aligned_grasp, collision_free)) # visualize if specified if collision_free and config['vis'][ 'candidate_grasps']: logging.info('Grasp %d' % (aligned_grasp.id)) vis.figure() vis.gripper_on_object(gripper, aligned_grasp, obj, stable_pose.T_obj_world) vis.show() # save to file logging.info('Saving to file') pkl.dump(candidate_grasps_dict, open(grasp_cache_filename, 'wb')) # 2. Render a dataset of images and associate the gripper pose with image coordinates for each grasp in the Dex-Net database # setup variables obj_category_map = {} pose_category_map = {} cur_pose_label = 0 cur_obj_label = 0 cur_image_label = 0 # render images for each stable pose of each object in the dataset render_modes = [RenderMode.SEGMASK, RenderMode.DEPTH_SCENE] for dataset in datasets: logging.info('Generating data for dataset %s' % (dataset.name)) # iterate through all object keys object_keys = dataset.object_keys for obj_key in object_keys: obj = dataset[obj_key] if obj.key not in target_object_keys[dataset.name]: continue # read in the stable poses of the mesh stable_poses = dataset.stable_poses(obj.key) for i, stable_pose in enumerate(stable_poses): # render images if stable pose is valid if stable_pose.p > stable_pose_min_p: # log progress logging.info('Rendering images for object %s in %s' % (obj.key, stable_pose.id)) # add to category maps if obj.key not in obj_category_map.keys(): obj_category_map[obj.key] = cur_obj_label pose_category_map['%s_%s' % (obj.key, stable_pose.id)] = cur_pose_label # read in candidate grasps and metrics candidate_grasp_info = candidate_grasps_dict[obj.key][ stable_pose.id] candidate_grasps = [g.grasp for g in candidate_grasp_info] grasp_metrics = dataset.grasp_metrics(obj.key, candidate_grasps, gripper=gripper.name) # compute object pose relative to the table T_obj_stp = stable_pose.T_obj_table.as_frames('obj', 'stp') T_obj_stp = obj.mesh.get_T_surface_obj(T_obj_stp) # sample images from random variable T_table_obj = RigidTransform(from_frame='table', to_frame='obj') scene_objs = { 'table': SceneObject(table_mesh, T_table_obj) } urv = UniformPlanarWorksurfaceImageRandomVariable( obj.mesh, render_modes, 'camera', env_rv_params, stable_pose=stable_pose, scene_objs=scene_objs) render_start = time.time() render_samples = urv.rvs( size=image_samples_per_stable_pose) render_stop = time.time() logging.info('Rendering images took %.3f sec' % (render_stop - render_start)) # visualize if config['vis']['rendered_images']: d = int(np.ceil( np.sqrt(image_samples_per_stable_pose))) # binary vis2d.figure() for j, render_sample in enumerate(render_samples): vis2d.subplot(d, d, j + 1) vis2d.imshow(render_sample.renders[ RenderMode.SEGMASK].image) # depth table vis2d.figure() for j, render_sample in enumerate(render_samples): vis2d.subplot(d, d, j + 1) vis2d.imshow(render_sample.renders[ RenderMode.DEPTH_SCENE].image) vis2d.show() # tally total amount of data num_grasps = len(candidate_grasps) num_images = image_samples_per_stable_pose num_save = num_images * num_grasps logging.info('Saving %d datapoints' % (num_save)) # for each candidate grasp on the object compute the projection # of the grasp into image space for render_sample in render_samples: # read images binary_im = render_sample.renders[ RenderMode.SEGMASK].image depth_im_table = render_sample.renders[ RenderMode.DEPTH_SCENE].image # read camera params T_stp_camera = render_sample.camera.object_to_camera_pose shifted_camera_intr = render_sample.camera.camera_intr # read pixel offsets cx = depth_im_table.center[1] cy = depth_im_table.center[0] # compute intrinsics for virtual camera of the final # cropped and rescaled images camera_intr_scale = float(im_final_height) / float( im_crop_height) cropped_camera_intr = shifted_camera_intr.crop( im_crop_height, im_crop_width, cy, cx) final_camera_intr = cropped_camera_intr.resize( camera_intr_scale) # create a thumbnail for each grasp for grasp_info in candidate_grasp_info: # read info grasp = grasp_info.grasp collision_free = grasp_info.collision_free # get the gripper pose T_obj_camera = T_stp_camera * T_obj_stp.as_frames( 'obj', T_stp_camera.from_frame) grasp_2d = grasp.project_camera( T_obj_camera, shifted_camera_intr) # center images on the grasp, rotate to image x axis dx = cx - grasp_2d.center.x dy = cy - grasp_2d.center.y translation = np.array([dy, dx]) binary_im_tf = binary_im.transform( translation, grasp_2d.angle) depth_im_tf_table = depth_im_table.transform( translation, grasp_2d.angle) # crop to image size binary_im_tf = binary_im_tf.crop( im_crop_height, im_crop_width) depth_im_tf_table = depth_im_tf_table.crop( im_crop_height, im_crop_width) # resize to image size binary_im_tf = binary_im_tf.resize( (im_final_height, im_final_width), interp='nearest') depth_im_tf_table = depth_im_tf_table.resize( (im_final_height, im_final_width)) # visualize the transformed images if config['vis']['grasp_images']: grasp_center = Point( depth_im_tf_table.center, frame=final_camera_intr.frame) tf_grasp_2d = Grasp2D( grasp_center, 0, grasp_2d.depth, width=gripper.max_width, camera_intr=final_camera_intr) # plot 2D grasp image vis2d.figure() vis2d.subplot(2, 2, 1) vis2d.imshow(binary_im) vis2d.grasp(grasp_2d) vis2d.subplot(2, 2, 2) vis2d.imshow(depth_im_table) vis2d.grasp(grasp_2d) vis2d.subplot(2, 2, 3) vis2d.imshow(binary_im_tf) vis2d.grasp(tf_grasp_2d) vis2d.subplot(2, 2, 4) vis2d.imshow(depth_im_tf_table) vis2d.grasp(tf_grasp_2d) vis2d.title('Coll Free? %d' % (grasp_info.collision_free)) vis2d.show() # plot 3D visualization vis.figure() T_obj_world = vis.mesh_stable_pose( obj.mesh, stable_pose.T_obj_world, style='surface', dim=0.5) vis.gripper(gripper, grasp, T_obj_world, color=(0.3, 0.3, 0.3)) vis.show() # form hand pose array hand_pose = np.r_[grasp_2d.center.y, grasp_2d.center.x, grasp_2d.depth, grasp_2d.angle, grasp_2d.center.y - shifted_camera_intr.cy, grasp_2d.center.x - shifted_camera_intr.cx, grasp_2d.width_px] # store to data buffers tensor_datapoint[ 'depth_ims_tf_table'] = depth_im_tf_table.raw_data tensor_datapoint[ 'obj_masks'] = binary_im_tf.raw_data tensor_datapoint['hand_poses'] = hand_pose tensor_datapoint['collision_free'] = collision_free tensor_datapoint['obj_labels'] = cur_obj_label tensor_datapoint['pose_labels'] = cur_pose_label tensor_datapoint['image_labels'] = cur_image_label for metric_name, metric_val in grasp_metrics[ grasp.id].iteritems(): coll_free_metric = ( 1 * collision_free) * metric_val tensor_datapoint[ metric_name] = coll_free_metric tensor_dataset.add(tensor_datapoint) # update image label cur_image_label += 1 # update pose label cur_pose_label += 1 # force clean up gc.collect() # update object label cur_obj_label += 1 # force clean up gc.collect() # save last file tensor_dataset.flush() # save category mappings obj_cat_filename = os.path.join(output_dir, 'object_category_map.json') json.dump(obj_category_map, open(obj_cat_filename, 'w')) pose_cat_filename = os.path.join(output_dir, 'pose_category_map.json') json.dump(pose_category_map, open(pose_cat_filename, 'w'))
to_frame="primesense_overhead") # T_world_camera = RigidTransform(rotation = np.array([[1,0,0],[0,1,0],[0,0,1]]), # translation=np.array([-.2,0,0]).T, # from_frame="world", # to_frame="primesense_overhead") # squares = [(-1,-1), (-1,0), (-1,1), (0,-1), (0,1), (1,-1), (1,0), (1,1)] # for i, square in enumerate(squares): T_rook2_world = RigidTransform(rotation=np.eye(3), translation=np.array([.06, .06, 0]).T, from_frame="rook2", to_frame="obj") of2 = ObjFile(dexnet_path + "/data/meshes/chess_pieces/WizRook.obj") rook2 = of2.read() camera.add_to_scene("rook2", SceneObject(rook2, T_rook2_world)) T_table_world = RigidTransform(rotation=np.eye(3), translation=np.array([0, 0, -.0025]).T, from_frame="table", to_frame="obj") of3 = ObjFile(dexnet_path + "/data/meshes/Table_triangulated_faces_resized.obj") table = of3.read() camera.add_to_scene("table", SceneObject(table, T_table_world)) of3 = ObjFile(dexnet_path + "/data/meshes/chess_pieces/WizRook.obj") rook3 = of3.read() T_rook3_world = RigidTransform(rotation=np.eye(3), translation=np.array([-.06, .06, 0]).T, from_frame="rook3",
def render_data(self): logging.basicConfig(level=logging.WARNING) for dataset in self.datasets: logging.info('Generating data for dataset %s' % dataset.name) object_keys = dataset.object_keys for obj_key in object_keys: logging.info("Object number: %d" % self.cur_obj_label) self.obj = dataset[obj_key] grasps = dataset.grasps(self.obj.key, gripper=self.gripper.name) positive_grasps = self.get_positive_grasps(dataset, grasps) # Load grasp metrics grasp_metrics = dataset.grasp_metrics( self.obj.key, grasps, gripper=self.gripper.name) # setup collision checker collision_checker = GraspCollisionChecker(self.gripper) collision_checker.set_graspable_object(self.obj) # read in the stable poses of the mesh stable_poses = dataset.stable_poses(self.obj.key) # Iterate through stable poses for i, stable_pose in enumerate(stable_poses): if not stable_pose.p > self._stable_pose_min_p: continue # setup table in collision checker T_obj_stp = stable_pose.T_obj_table.as_frames('obj', 'stp') T_obj_table = self.obj.mesh.get_T_surface_obj( T_obj_stp, delta=self._table_offset).as_frames('obj', 'table') T_table_obj = T_obj_table.inverse() T_obj_stp = self.obj.mesh.get_T_surface_obj(T_obj_stp) collision_checker.set_table(self._table_mesh_filename, T_table_obj) # sample images from random variable T_table_obj = RigidTransform(from_frame='table', to_frame='obj') scene_objs = { 'table': SceneObject(self.table_mesh, T_table_obj) } # Set up image renderer for _ in range(self.config['images_per_stable_pose']): elev_angle = np.random.choice( self.camera_distributions) camera_config = self._camera_configs() camera_config['min_elev'] = elev_angle * 5.0 camera_config['max_elev'] = (elev_angle + 1) * 5.0 sample = self.render_images( scene_objs, stable_pose, 1, camera_config=camera_config) self.save_samples(sample, grasps, T_obj_stp, collision_checker, grasp_metrics) # Get camera elevation angle for current sample elev_angle = sample.camera.elev * 180 / np.pi elev_bar = int(elev_angle // 5) # Sample number of positive images from distribution number_positive_images = np.random.choice( self.grasp_upsample_distribuitions[elev_bar]) # Render only positive images new_config = self._camera_configs() new_config['min_elev'] = elev_angle new_config['max_elev'] = elev_angle positive_render_samples = self.render_images( scene_objs, stable_pose, number_positive_images, camera_config=new_config) if type(positive_render_samples) == list: for pos_sample in positive_render_samples: self.save_samples(pos_sample, positive_grasps, T_obj_stp, collision_checker, grasp_metrics, only_positive=True) else: self.save_samples(positive_render_samples, positive_grasps, T_obj_stp, collision_checker, grasp_metrics, only_positive=True) self.cur_pose_label += 1 gc.collect() # next stable pose self.cur_obj_label += 1 # next object # Save dataset self.tensor_dataset.flush()
obj_key = dataset.object_keys[0] obj = dataset[obj_key] # read in the stable poses of the mesh stable_poses = dataset.stable_poses(obj.key) stable_pose = stable_poses[0] # setup table in collision checker T_obj_stp = stable_pose.T_obj_table.as_frames('obj', 'stp') T_obj_table = obj.mesh.get_T_surface_obj(T_obj_stp, delta=table_offset).as_frames( 'obj', 'table') # sample images from random variable T_table_obj = RigidTransform(from_frame='table', to_frame='obj') scene_objs = {'table': SceneObject(table_mesh, T_table_obj)} # Set up image renderer deltas = np.arange(0, 0.4, 0.05) camera_dist = config['env_rv_params']['min_radius'] for delta in deltas: config['env_rv_params']['min_radius'] = camera_dist + delta config['env_rv_params']['max_radius'] = camera_dist + delta urv = UniformPlanarWorksurfaceImageRandomVariable(obj.mesh, [RenderMode.DEPTH_SCENE], 'camera', config['env_rv_params'], scene_objs=scene_objs, stable_pose=stable_pose) # Render images
specular=0.25, T_light_camera=T_light_camera, cutoff=180) # create material props mat_props = MaterialProperties(color=(249, 241, 21), ambient=0.5, diffuse=1.0, specular=1, shininess=0) # create scene objects scene_objs = { 'table': SceneObject(table_mesh, T_obj_world.inverse(), mat_props=table_mat_props) } for name, scene_obj in scene_objs.iteritems(): virtual_camera.add_to_scene(name, scene_obj) # camera pose cam_dist = 0.3 T_camera_world = RigidTransform(rotation=np.array([[0, 1, 0], [1, 0, 0], [0, 0, -1]]), translation=[0, 0, cam_dist], from_frame=camera_intr.frame, to_frame='world') T_obj_camera = T_camera_world.inverse() * T_obj_world