vprdb.providers.depth_image_provider
1# Copyright (c) 2023, Ivan Moskalenko, Anastasiia Kornilova 2# 3# Licensed under the Apache License, Version 2.0 (the "License"); 4# you may not use this file except in compliance with the License. 5# You may obtain a copy of the License at 6# 7# http://www.apache.org/licenses/LICENSE-2.0 8# 9# Unless required by applicable law or agreed to in writing, software 10# distributed under the License is distributed on an "AS IS" BASIS, 11# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12# See the License for the specific language governing permissions and 13# limitations under the License. 14import cv2 15import open3d as o3d 16 17from dataclasses import dataclass 18from nptyping import Float, NDArray, Shape 19from pathlib import Path 20 21 22@dataclass(frozen=True) 23class DepthImageProvider: 24 """Depth image provider is a wrapper for depth images""" 25 26 path: Path 27 """Path to the file on the hard drive""" 28 intrinsics: NDArray[Shape["3, 3"], Float] 29 """Intrinsic camera parameters""" 30 depth_scale: int 31 """Depth scale for transforming depth""" 32 33 @property 34 def point_cloud(self) -> o3d.geometry.PointCloud: 35 """Returns Open3D point cloud constructed from depth image""" 36 depth_image = cv2.imread(str(self.path), cv2.IMREAD_ANYDEPTH) 37 height, width = depth_image.shape 38 depth_image = o3d.geometry.Image(depth_image) 39 intrinsics = o3d.camera.PinholeCameraIntrinsic(width, height, self.intrinsics) 40 point_cloud = o3d.geometry.PointCloud.create_from_depth_image( 41 depth_image, 42 intrinsics, 43 depth_scale=self.depth_scale, 44 depth_trunc=float("inf"), 45 ) 46 return point_cloud
@dataclass(frozen=True)
class
DepthImageProvider:
23@dataclass(frozen=True) 24class DepthImageProvider: 25 """Depth image provider is a wrapper for depth images""" 26 27 path: Path 28 """Path to the file on the hard drive""" 29 intrinsics: NDArray[Shape["3, 3"], Float] 30 """Intrinsic camera parameters""" 31 depth_scale: int 32 """Depth scale for transforming depth""" 33 34 @property 35 def point_cloud(self) -> o3d.geometry.PointCloud: 36 """Returns Open3D point cloud constructed from depth image""" 37 depth_image = cv2.imread(str(self.path), cv2.IMREAD_ANYDEPTH) 38 height, width = depth_image.shape 39 depth_image = o3d.geometry.Image(depth_image) 40 intrinsics = o3d.camera.PinholeCameraIntrinsic(width, height, self.intrinsics) 41 point_cloud = o3d.geometry.PointCloud.create_from_depth_image( 42 depth_image, 43 intrinsics, 44 depth_scale=self.depth_scale, 45 depth_trunc=float("inf"), 46 ) 47 return point_cloud
Depth image provider is a wrapper for depth images