facebookresearch / habitat-sim

A flexible, high-performance 3D simulator for Embodied AI research.
https://aihabitat.org/
MIT License
2.58k stars 419 forks source link

How to convert depth image of equirect_depth_sensor to pointcloud? #1953

Open fangchuan opened 1 year ago

fangchuan commented 1 year ago

Hi, I have rendered rgb/depth/semantic image from equirect_color_sensor/equirect_depth_sensor/equirect_semantic_sensor respectively. The rgb image seems fine, but I the value of depth image probably be wrong. Specificly,

  1. first, I render the depth image from equirect_depth_sensor and save it;
  2. then I turn the equirectangular depth image into pointcloud by spherical projecting;
  3. finally I save the pointcloud.

  1. code of step 1:

    def save_depth_observation(self, obs, sensor_uuid, total_frames, output_folder):
        if not (sensor_uuid in obs.keys()):
            print(f'observation doesnt contain sensor:{sensor_uuid}')
            exit(-1)
    
        depth_obs = obs[sensor_uuid]
        depth_img = Image.fromarray((depth_obs / 10 * 255).astype(np.uint8), mode="L")
        if self._demo_type == DemoRunnerType.AB_TEST:
            if self._group_id == ABTestGroup.CONTROL:
                filepath = os.path.join(output_folder, "test.depth.control.png")
                depth_img.save(filepath)
            else:
                filepath = os.path.join(output_folder, "test.depth.test.png" )
                depth_img.save(filepath)
        else:
            filepath = os.path.join(output_folder, "depth.png")
            depth_img.save(filepath)
      if self._sim_settings["equirect_depth_sensor"]:
          self.save_depth_observation(observations, "equirect_depth_sensor", total_frames, scene_folderpath)
  2. code of step 2 and 3:

    def get_unit_spherical_map():
        h = 512
        w = 1024
        Theta = np.arange(h).reshape(h, 1) * np.pi / h + np.pi / h / 2
        Theta = np.repeat(Theta, w, axis=1)
        Phi = np.arange(w).reshape(1, w) * 2 * np.pi / w + np.pi / w - np.pi
        Phi = -np.repeat(Phi, h, axis=0)
    
        X = np.expand_dims(np.sin(Theta) * np.sin(Phi),2)
        Y =  np.expand_dims(np.cos(Theta),2)
        Z = np.expand_dims(np.sin(Theta) * np.cos(Phi),2)
        unit_map = np.concatenate([X,Z,Y],axis=2)
    
        return unit_map
    
    depth_img_filepath = '/media/ziqianbai/BACKPACK_DATA1/Replica_all/replica/room_0/00000/depth.png'
    depth_img = np.asarray(Image.open(depth_img_filepath))
    depth_img=np.expand_dims((depth_img*10.0/255),axis=2)
    pointcloud = depth_img * get_unit_spherical_map()
  3. code of step 3:

    o3d_pointcloud = o3d.geometry.PointCloud()
    o3d_pointcloud.points = o3d.utility.Vector3dVector(pointcloud.reshape(-1,3))
    o3d.io.write_point_cloud('/media/ziqianbai/BACKPACK_DATA1/Replica_all/replica/frl_apartment_0/00000/pcl.ply', o3d_pointcloud)
  4. configuration: habitat-sim: 0.2.0 platform: ubuntu18.04

    But the pointcloud is totally twisted, I want you to help me figure out if there is any problems during my processing codes. @aclegg3 @0mdc @dhruvbatra Thanks in advance! the output pointcloud of scene frl_apartment_0: replica_v1

aclegg3 commented 1 year ago

@Skylion007 thoughts?

fangchuan commented 1 year ago

Well, I haved digged into this problem, one cue is that the equirect_depth_image seems been stitched by 6 cubemap perspective images. Then I generate 6 cubic faces from the equirect_depth_image and unproject these cubic subviews' depth images to pointclouds, they looks ok, But the precision seems not good, the depth is likely been truncated cause of inappropriate depth scale or depth image format: image image image image

Finally, I merged 6 pointclouds generated by cubic subviews and get the following pointcloud: image

matsuren commented 1 year ago

I also confirmed that the depth map of equirectangular images is not correct, which I fixed this bug for python implementation in https://github.com/facebookresearch/habitat-lab/pull/517 You can see the details explanation here.

If I remembered correctly, they changed the implementation from python to magnum, so the bug might be included during that process. But I'm not familiar with magnum so I can't help with this.