Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open3D pointcloud from D405 can't sense object further than 15cm #11960

Closed
leets0429 opened this issue Jul 3, 2023 · 5 comments
Closed

Open3D pointcloud from D405 can't sense object further than 15cm #11960

leets0429 opened this issue Jul 3, 2023 · 5 comments

Comments

@leets0429
Copy link


Required Info
Camera Model Intel Realsense D405
Firmware Version 2.53.1
Operating System & Version Ubuntu 20.04
Kernel Version (Linux Only) 5.15.0-76-generic
Platform PC
SDK Version pyrealsense2 2.53.1.4623, open3d 0.16.0
Language python
Segment robot

Issue Description

I'm able to get pointcloud in Open3D format, however if objects are further than around 15cm, they no longer appear in the pointcloud. This doesn't make sense as I tried the example script with opencv viewer, it could sense object much further away. I'm not sure is this a Open3D or Intel Realsense issue. Hence I will post at both places. Below is my code:

import open3d as o3d

depth_cam = o3d.t.io.RealSenseSensor()
depth_cam.start_capture()
device = 'cuda:0' if o3d.core.cuda.is_available() else 'cpu:0'
o3d_device = o3d.core.Device(device)
intrinsic_matrix = o3d.core.Tensor(depth_cam.get_metadata().intrinsics.intrinsic_matrix, dtype=o3d.core.Dtype.Float32, device=o3d_device) 
im_rgbd = depth_cam.capture_frame(True, True)
pcd = o3d.t.geometry.PointCloud.create_from_rgbd_image(im_rgbd, intrinsic_matrix).to_legacy()

try:
    while True:

        im_rgbd = depth_cam.capture_frame(True, True)
        pcd = o3d.t.geometry.PointCloud.create_from_rgbd_image(im_rgbd, intrinsic_matrix).to_legacy()
        o3d.visualization.draw_geometries([pcd])

finally:
    pass
@MartyG-RealSense
Copy link
Collaborator

Hi @leets0429 There is a recent Python / Open3D pointcloud case with D405 at #11921 that you can compare to your own issue to see if they have similarities.

@leets0429
Copy link
Author

@MartyG-RealSense Thank for the reference.

Instead of using the RealSenseSensor from o3d to create a pointcloud, I have to read the pointcloud using the Intel pipeline, convert it to numpy array and then convert it to o3d format

I adapted my code and now I can get the complete o3d pointcloud.

Here's my working code for others to refer:

from datetime import datetime
import pyrealsense2 as rs
import numpy as np
import open3d as o3d
    
# Create a pipeline
pipeline = rs.pipeline()

# Create a config and configure the pipeline to stream
#  different resolutions of color and depth streams
config = rs.config()
config.enable_stream(rs.stream.depth, 640, 480, rs.format.z16, 30)
config.enable_stream(rs.stream.color, 640, 480, rs.format.rgb8, 30)

# Start streaming
profile = pipeline.start(config)

# Streaming loop
try:
    vis = o3d.visualization.Visualizer()
    vis.create_window("Tests")
    pcd = o3d.geometry.PointCloud()
    while True:
        dt0 = datetime.now()
        vis.add_geometry(pcd)
        pcd.clear()
        # Get frameset of color and depth
        frames = pipeline.wait_for_frames()
        color = frames.get_color_frame()
        colors = np.asanyarray(color.get_data())
        depth = frames.get_depth_frame()
        if not color or not depth:
            continue
        pc = rs.pointcloud()
        pc.map_to(color)
        points = pc.calculate(depth)
        vtx = np.asanyarray(points.get_vertices())
        vtx = vtx.view(np.float32).reshape(-1, 3)
        clr = colors.reshape(-1, 3) / 255.0
        pcd.points = o3d.utility.Vector3dVector(vtx)
        pcd.colors = o3d.utility.Vector3dVector(clr)

        vis.update_geometry(pcd)
        vis.poll_events()
        vis.update_renderer()
        process_time = datetime.now() - dt0
        print("FPS = {0}".format(1/process_time.total_seconds()))

finally:
    pipeline.stop()

@MartyG-RealSense
Copy link
Collaborator

It's great to hear that you were successful. Thanks very much for the update and for sharing your solution!

@Gowthers
Copy link

Hey,
I have a different solution for your problem since I also encountered it. The D405 is the only realsense camera that has a depth scale of 0.01 instead of 0.001 (#11784 (comment)). Since I create the pointcloud from the image and the depth map as a np array, when combining the two into one RGBD image in open3d, I just have to adapt the depth scale to show properly.

import open3d as o3d
# serial number of the 405
the_dev = '222222222222'

depth_intrinsics = device.pipeline_profile.get_stream(rs.stream.depth).as_video_stream_profile().get_intrinsics() 
# ^^ this line uses my own device class, you will have to get the intrinsic from the pipeline

# Get saved color, depth and colorised depth data from folder
color = o3d.io.read_image(f"test_frames/{the_dev}img.png")
depth = o3d.io.read_image(f"test_frames/{the_dev}depth.png")
colorised_depth = o3d.io.read_image(f"test_frames/{the_dev}colorized_depth.png")

# Create an RGB-D image object from the color and depth images
if the_dev == '222222222222': 
    rgbd = o3d.geometry.RGBDImage.create_from_color_and_depth(color, depth, depth_scale=10000, convert_rgb_to_intensity=False)
else:
    rgbd = o3d.geometry.RGBDImage.create_from_color_and_depth(color, depth,
                                                              convert_rgb_to_intensity=False)

# Get own camera intrinsics
pinhole_depth_camera_intrinsics = o3d.camera.PinholeCameraIntrinsic(
    depth_intrinsics.width, depth_intrinsics.height,
    depth_intrinsics.fx, depth_intrinsics.fy,
    depth_intrinsics.ppx, depth_intrinsics.ppy
)

# Create a point cloud object from the RGB-D image and the camera intrinsics
pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd, pinhole_depth_camera_intrinsics)

# Flip the orientation of the point cloud, so it looks upright
pcd.transform([[1, 0, 0, 0],
               [0, -1, 0, 0],
               [0, 0, -1, 0],
               [0, 0, 0, 1]])

# display pointcloud:
o3d.visualization.draw_geometries([pcd])

@MartyG-RealSense
Copy link
Collaborator

Thanks so much @Gowthers for sharing your own solution!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

3 participants