Skip to content

RSDK-857 - add pcd docs #202

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

Merged
merged 1 commit into from
Jan 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions src/viam/components/camera/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,20 @@ async def get_point_cloud(self, *, timeout: Optional[float] = None, **kwargs) ->
should encode the bytes into the formatted suggested
by the mimetype.

To deserialize the returned information into a numpy array, use the Open3D library.
::

import numpy as np
import open3d as o3d

data, _ = await camera.get_point_cloud()

# write the point cloud into a temporary file
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can probably use a BytesIO buffer rather than writing out to a file in case there are permissions issues with writing to disk

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

unfortunately the api only takes file name as input arg isl-org/Open3D#1146

with open("/tmp/pointcloud_data.pcd", "wb") as f:
f.write(data)
pcd = o3d.io.read_point_cloud("/tmp/pointcloud_data.pcd")
points = np.asarray(pcd.points)

Returns:
bytes: The pointcloud data.
str: The mimetype of the pointcloud (e.g. PCD).
Expand Down
14 changes: 14 additions & 0 deletions src/viam/services/vision.py
Original file line number Diff line number Diff line change
Expand Up @@ -341,6 +341,20 @@ async def get_object_point_clouds(
Returns a list of the 3D point cloud objects and associated metadata in the latest
picture obtained from the specified 3D camera (using the specified segmenter).

To deserialize the returned information into a numpy array, use the Open3D library.
::

import numpy as np
import open3d as o3d

object_point_clouds = await vision.get_object_point_clouds(camera_name, segmenter_name)

# write the first object point cloud into a temporary file
with open("/tmp/pointcloud_data.pcd", "wb") as f:
f.write(object_point_clouds[0].point_cloud)
pcd = o3d.io.read_point_cloud("/tmp/pointcloud_data.pcd")
points = np.asarray(pcd.points)

Args:
camera_name (str): The name of the camera
segmenter_name (str): The name of the segmenter
Expand Down