def create_grid_image(inputs, outputs, labels, max_num_images_to_save=3): '''Make a grid of images for display purposes Size of grid is (3, N, 3), where each coloum belongs to input, output, label resp Args: inputs (Tensor): Batch Tensor of shape (B x C x H x W) outputs (Tensor): Batch Tensor of shape (B x C x H x W) labels (Tensor): Batch Tensor of shape (B x C x H x W) max_num_images_to_save (int, optional): Defaults to 3. Out of the given tensors, chooses a max number of imaged to put in grid Returns: numpy.ndarray: A numpy array with of input images arranged in a grid ''' img_tensor = inputs[:max_num_images_to_save] output_tensor = outputs[:max_num_images_to_save] output_tensor_rgb = normal_to_rgb(output_tensor) label_tensor = labels[:max_num_images_to_save] mask_invalid_pixels = torch.all(label_tensor == 0, dim=1, keepdim=True) mask_invalid_pixels = (torch.cat([mask_invalid_pixels] * 3, dim=1)).byte() label_tensor_rgb = normal_to_rgb(label_tensor) label_tensor_rgb[mask_invalid_pixels] = 0 cos = nn.CosineSimilarity(dim=1, eps=1e-6) x = cos(output_tensor, label_tensor) # loss_cos = 1.0 - x loss_rad = torch.acos(x) loss_rad_rgb = np.zeros((loss_rad.shape[0], 3, loss_rad.shape[1], loss_rad.shape[2]), dtype=np.float32) for idx, img in enumerate(loss_rad.numpy()): error_rgb = api_utils.depth2rgb(img, min_depth=0.0, max_depth=1.57, color_mode=cv2.COLORMAP_PLASMA, reverse_scale=False) loss_rad_rgb[idx] = error_rgb.transpose(2, 0, 1) / 255 loss_rad_rgb = torch.from_numpy(loss_rad_rgb) loss_rad_rgb[mask_invalid_pixels] = 0 mask_invalid_pixels_rgb = torch.ones_like(img_tensor) mask_invalid_pixels_rgb[mask_invalid_pixels] = 0 images = torch.cat((img_tensor, output_tensor_rgb, label_tensor_rgb, loss_rad_rgb, mask_invalid_pixels_rgb), dim=3) # grid_image = make_grid(images, 1, normalize=True, scale_each=True) grid_image = make_grid(images, 1, normalize=False, scale_each=False) return grid_image
input_depth = depthcomplete.input_depth surface_normals = depthcomplete.surface_normals surface_normals_rgb = depthcomplete.surface_normals_rgb occlusion_weight = depthcomplete.occlusion_weight occlusion_weight_rgb = depthcomplete.occlusion_weight_rgb outlines_rgb = depthcomplete.outlines_rgb # save depth complete input depth nparrayfn = f'./viz/data/d415/{dt}_d415_dp_input_depth.npy' with open(nparrayfn, 'wb') as f: np.save(f, input_depth) # Display Results in Window input_depth_mapped = utils.depth2rgb( input_depth, min_depth=config.depthVisualization.minDepth, max_depth=config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) output_depth_mapped = utils.depth2rgb( output_depth, min_depth=config.depthVisualization.minDepth, max_depth=config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) filtered_output_depth_mapped = utils.depth2rgb( filtered_output_depth, min_depth=config.depthVisualization.minDepth, max_depth=config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) color_img = cv2.cvtColor(color_img, cv2.COLOR_RGB2BGR)
print('output max/min1:', output.max(), output.min()) output = np.clip(output, 1, 100) output = DepthNorm(output) # De-Normalizing depth label = DepthNorm(label) # De-Normalizing depth print('label max/min2:', label.max(), label.min()) print('output max/min2:', output.max(), output.min()) output = (output / 1000) * 3.0 label = (label / 1000) * 3.0 print('label max/min3:', label.max(), label.min()) print('output max/min3:', output.max(), output.min()) output_rgb = api_utils.depth2rgb(output, config.train.min_depth, config.train.max_depth) label_rgb = api_utils.depth2rgb(label, config.train.min_depth, config.train.max_depth) numpy_grid = np.concatenate((input, output_rgb, label_rgb), axis=1) imageio.imwrite(result_path, numpy_grid) # Save Point Cloud ptcloud_path = os.path.join( RESULTS_DIR, '{:09d}-output-ptcloud.ply'.format(ii * config.eval.batchSize + iii)) print('img {:09d} min-depth {} max-depth {}'.format( ii * config.eval.batchSize + iii, output.min(), output.max())) fov_x = 69.4 # degrees
def callback(self, ros_rgb_image, ros_depth_image): #rospy.loginfo('synched callback') cv_bridge = CvBridge() try: rgb_image = cv_bridge.compressed_imgmsg_to_cv2( ros_rgb_image, desired_encoding='passthrough') depth_image = cv_bridge.imgmsg_to_cv2( ros_depth_image, desired_encoding='passthrough') except e: print(e) color_img, input_depth = rgb_image, np.array(depth_image, dtype=np.float32) try: output_depth, filtered_output_depth = depthcomplete.depth_completion( color_img, input_depth, inertia_weight=float(self.config.depth2depth.inertia_weight), smoothness_weight=float( self.config.depth2depth.smoothness_weight), tangent_weight=float(self.config.depth2depth.tangent_weight), mode_modify_input_depth=self.config.modifyInputDepth.mode) except depth_completion_api.DepthCompletionError as e: print('Depth Completion Failed:\n {}\n ...skipping image {}'. format(e, i)) color_img = depthcomplete.input_image input_depth = depthcomplete.input_depth surface_normals = depthcomplete.surface_normals surface_normals_rgb = depthcomplete.surface_normals_rgb occlusion_weight = depthcomplete.occlusion_weight occlusion_weight_rgb = depthcomplete.occlusion_weight_rgb outlines_rgb = depthcomplete.outlines_rgb # Display Results in Window input_depth_mapped = utils.depth2rgb( input_depth, min_depth=self.config.depthVisualization.minDepth, max_depth=self.config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) output_depth_mapped = utils.depth2rgb( output_depth, min_depth=self.config.depthVisualization.minDepth, max_depth=self.config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) filtered_output_depth_mapped = utils.depth2rgb( filtered_output_depth, min_depth=self.config.depthVisualization.minDepth, max_depth=self.config.depthVisualization.maxDepth, color_mode=cv2.COLORMAP_JET, reverse_scale=True) color_img = cv2.cvtColor(color_img, cv2.COLOR_RGB2BGR) surface_normals_rgb = cv2.cvtColor(surface_normals_rgb, cv2.COLOR_RGB2BGR) outlines_rgb = cv2.cvtColor(outlines_rgb, cv2.COLOR_RGB2BGR) occlusion_weight_rgb = cv2.cvtColor(occlusion_weight_rgb, cv2.COLOR_RGB2BGR) grid_image1 = np.concatenate((color_img, surface_normals_rgb, outlines_rgb, occlusion_weight_rgb), 1) grid_image2 = np.concatenate( (input_depth_mapped, output_depth_mapped, filtered_output_depth_mapped, np.zeros(color_img.shape, dtype=color_img.dtype)), 1) grid_image = np.concatenate((grid_image1, grid_image2), 0) # Publish final depth image self.final_depth_msg = CvBridge().cv2_to_imgmsg( filtered_output_depth_mapped) #self.publisher.publish(final_depth_msg) cv2.imshow('Live Demo', grid_image) keypress = cv2.waitKey(1) if keypress & 0xFF == ord('q'): cv2.destroyAllWindows() if keypress & 0xFF == ord('s') or keypress == 13: # Save captured data to config.captures_dir depthcomplete.store_depth_completion_outputs( captures_dir, self.capture_num, min_depth=self.config.depthVisualization.minDepth, max_depth=self.config.depthVisualization.maxDepth) print('captured image {0:06d}'.format(self.capture_num)) self.capture_num += 1