How can I get pointcloud from Realsense D455 in Isaac Sim Asset?

Hello guys, thank you for reading. I’m trying to get pointcloud from RSD455 asset of isaac sim, but it won’t work.
This is my code.

create_prim("/World/Realsense_bottom", "Xform")
bottom_parent = stage.GetPrimAtPath("/World/Realsense_bottom")
UsdGeom.XformCommonAPI(bottom_parent).SetTranslate((-0.09938172401020395, -0.02812370593180794, 0.9132709956171814))

# bottom_quat = [0.9829, 0.0, 0.1841, 0.0]
euler_bottom = (0,21.21749,0)
UsdGeom.XformCommonAPI(bottom_parent).SetRotate(tuple(euler_bottom))
# create_prim_with_ref("/World/Realsense_bottom/RSD455", realsense_asset_path)
# sensor_bottom = stage.GetPrimAtPath("/World/Realsense_bottom/RSD455")
create_prim_with_ref("/World/Realsense_bottom", realsense_asset_path)
sensor_bottom = stage.GetPrimAtPath("/World/Realsense_bottom")
# UsdGeom.XformCommonAPI(sensor_bottom).SetTranslate((0, 0, 0))
rb_bottom = UsdPhysics.RigidBodyAPI.Get(stage, sensor_bottom.GetPath())
if rb_bottom:
    rb_bottom.CreateRigidBodyEnabledAttr().Set(False)
else:
    for child in sensor_bottom.GetChildren():
        rb_child = UsdPhysics.RigidBodyAPI.Get(stage, child.GetPath())
        if rb_child:
            rb_child.CreateRigidBodyEnabledAttr().Set(False)

camera_depth = Camera(
    prim_path="/World/Realsense_bottom/RSD455/Camera_Pseudo_Depth",
    frequency=10,
    position = (0,0,0),
    resolution = (640,480),
    name="Camera"
)

camera_depth.initialize()

camera_depth.add_motion_vectors_to_frame()

camera_depth.add_distance_to_image_plane_to_frame()


while simulation_app.is_running():
    world.step(render=True)

    for _ in range(10):
        world.step(render=True)
        time.sleep(0.1)

    # Now retrieve the sensor data.
    rgb_image = camera_rgb.get_rgb()
    depth_image = camera_depth.get_depth()
    # intrinsics = camera_rgb.get_intrinsics_matrix()
    # Convert the depth to a point cloud.
    
    # pc, _ = depth2pc(depth_image, intrinsics, rgb_image)
    pointcloud = camera_depth.get_pointcloud()

#     # Visualize with Open3D.
    pcd = o3d.geometry.PointCloud()
    pcd.points = o3d.utility.Vector3dVector(pointcloud)
    o3d.visualization.draw_geometries([pcd])

    break
simulation_app.close()

And I get this error

Traceback (most recent call last):
  File "/home/rcv/Desktop/ws_voxposer/scene_standalone.py", line 242, in <module>
    pointcloud = camera_depth.get_pointcloud()
  File "/home/rcv/anaconda3/envs/isaac-sim/lib/python3.10/site-packages/isaacsim/exts/omni.isaac.sensor/omni/isaac/sensor/scripts/camera.py", line 1023, in get_pointcloud
    pointcloud = self.get_world_points_from_image_coords(points_2d, depth.flatten())
  File "/home/rcv/anaconda3/envs/isaac-sim/lib/python3.10/site-packages/isaacsim/exts/omni.isaac.sensor/omni/isaac/sensor/scripts/camera.py", line 1461, in get_world_points_from_image_coords
    raise Exception(
Exception: pinhole projection type is not set to be able to use get_world_points_from_image_coords method which use pinhole prespective projection.

I would be really thankful for any help.
Thank you.

Hi @yk_kim! Which version of Isaac Sim are you using?
For the Camera API, the projection type should be pinhole by default…

Hi @zhengwang , thank you for your answer. I’m using Isaac Sim 4.2.0

All I did was

  1. load the USD of RealsenseD455 asset with url.
realsense_asset_path = "http://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.2/Isaac/Sensors/Intel/RealSense/rsd455.usd"create_prim("/World/Realsense_bottom", "Xform")
bottom_parent = stage.GetPrimAtPath("/World/Realsense_bottom")
UsdGeom.XformCommonAPI(bottom_parent).SetTranslate((0.58, -0.47, 1.32))
bottom_quat = [0.9829, 0.0, 0.1841, 0.0]
euler_bottom = R.from_quat(bottom_quat).as_euler('XYZ', degrees=True)
UsdGeom.XformCommonAPI(bottom_parent).SetRotate(tuple(euler_bottom))
create_prim_with_ref("/World/Realsense_bottom/RSD455", realsense_asset_path)
sensor_bottom = stage.GetPrimAtPath("/World/Realsense_bottom/RSD455")
UsdGeom.XformCommonAPI(sensor_bottom).SetTranslate((0, 0, 0))
rb_bottom = UsdPhysics.RigidBodyAPI.Get(stage, sensor_bottom.GetPath())
rb_bottom.CreateRigidBodyEnabledAttr().Set(False)

  1. assign a new camera and get ready to grab a depth map
camera_depth = Camera(
    prim_path="/World/Realsense_bottom/RSD455/Camera_Pseudo_Depth",
    frequency=10,
    resolution = (640,480),
    translation=(0,0.0115,0),
    name="Camera"
)
camera_depth.initialize()
camera_depth.add_distance_to_image_plane_to_frame()

  1. get intrinsics for generating pointcloud (tried Camera.get_pointcloud() but it ended up with the same error below)
intrinsics = camera_depth.get_intrinsics_matrix()
  1. Error
(Pdb) camera_depth.get_intrinsics_matrix()
*** Exception: pinhole projection type is not set to be able to use get_intrinsics_matrix method.```

This is what I see right after importing RSD455 from Isaac Asset, and the projection type is set to fisheyeEquidistant..

Thanks! Please try manually setting the projection type to pinhole.

It did work, but the images are distorted, resulting in a low-quality point cloud.
What I’m worried about is why the projection type is set to fisheye in the first place.

Or is there a way to undistort my image? I failed with opencv, and I’m not sure about the reason. I guess it’s the parameters that are responsible for distortion.

We had it as fisheyeEquidistant because of the distortion. Let me reach out to the internal team to see if there is a way to address both distortion issue and getting point cloud.