open3d.geometry.PointCloud¶
-
class
open3d.geometry.
PointCloud
¶ PointCloud class. A point cloud consists of point coordinates, and optionally point colors and point normals.
-
class
Type
¶ Enum class for Geometry types.
-
HalfEdgeTriangleMesh
= Type.HalfEdgeTriangleMesh¶
-
Image
= Type.Image¶
-
LineSet
= Type.LineSet¶
-
PointCloud
= Type.PointCloud¶
-
RGBDImage
= Type.RGBDImage¶
-
TetraMesh
= Type.TetraMesh¶
-
TriangleMesh
= Type.TriangleMesh¶
-
Unspecified
= Type.Unspecified¶
-
VoxelGrid
= Type.VoxelGrid¶
-
-
__init__
(*args, **kwargs)¶ Overloaded function.
__init__(self: open3d.cpu.pybind.geometry.PointCloud) -> None
Default constructor
__init__(self: open3d.cpu.pybind.geometry.PointCloud, arg0: open3d.cpu.pybind.geometry.PointCloud) -> None
Copy constructor
__init__(self: open3d.cpu.pybind.geometry.PointCloud, points: open3d.cpu.pybind.utility.Vector3dVector) -> None
Create a PointCloud from points
-
clear
(self)¶ Clear all elements in the geometry.
- Returns
open3d.cpu.pybind.geometry.Geometry
-
cluster_dbscan
(self, eps, min_points, print_progress=False)¶ Cluster PointCloud using the DBSCAN algorithm Ester et al., ‘A Density-Based Algorithm for Discovering Clusters in Large Spatial Databases with Noise’, 1996. Returns a list of point labels, -1 indicates noise according to the algorithm.
- Parameters
eps (float) – Density parameter that is used to find neighbouring points.
min_points (int) – Minimum number of points to form a cluster.
print_progress (bool, optional, default=False) – If true the progress is visualized in the console.
- Returns
open3d.cpu.pybind.utility.IntVector
-
compute_convex_hull
(self)¶ Computes the convex hull of the point cloud.
- Returns
Tuple[open3d.geometry.TriangleMesh, List[int]]
-
compute_mahalanobis_distance
(self)¶ Function to compute the Mahalanobis distance for points in a point cloud. See: https://en.wikipedia.org/wiki/Mahalanobis_distance.
- Returns
open3d.cpu.pybind.utility.DoubleVector
-
compute_mean_and_covariance
(self)¶ Function to compute the mean and covariance matrix of a point cloud.
- Returns
Tuple[numpy.ndarray[float64[3, 1]], numpy.ndarray[float64[3, 3]]]
-
compute_nearest_neighbor_distance
(self)¶ Function to compute the distance from a point to its nearest neighbor in the point cloud
- Returns
open3d.cpu.pybind.utility.DoubleVector
-
compute_point_cloud_distance
(self, target)¶ For each point in the source point cloud, compute the distance to the target point cloud.
- Parameters
target (open3d.cpu.pybind.geometry.PointCloud) – The target point cloud.
- Returns
open3d.cpu.pybind.utility.DoubleVector
-
static
create_from_depth_image
(depth, intrinsic, extrinsic=(with default value), depth_scale=1000.0, depth_trunc=1000.0, stride=1, project_valid_depth_only=True)¶ - Factory function to create a pointcloud from a depth image and a
camera. Given depth value d at (u, v) image coordinate, the corresponding 3d point is:
z = d / depth_scale
x = (u - cx) * z / fx
y = (v - cy) * z / fy
- Parameters
depth (open3d.geometry.Image) – The input depth image can be either a float image, or a uint16_t image.
intrinsic (open3d.cpu.pybind.camera.PinholeCameraIntrinsic) – Intrinsic parameters of the camera.
extrinsic (numpy.ndarray[float64[4, 4]], optional) – array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]])
depth_scale (float, optional, default=1000.0) – The depth is scaled by 1 / depth_scale.
depth_trunc (float, optional, default=1000.0) – Truncated at depth_trunc distance.
stride (int, optional, default=1) – Sampling factor to support coarse point cloud extraction.
project_valid_depth_only (bool, optional, default=True) –
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
static
create_from_rgbd_image
(image, intrinsic, extrinsic=(with default value), project_valid_depth_only=True)¶ - Factory function to create a pointcloud from an RGB-D image and a camera. Given depth value d at (u, v) image coordinate, the corresponding 3d point is: - z = d / depth_scale
x = (u - cx) * z / fx
y = (v - cy) * z / fy
- Parameters
image (open3d.geometry.RGBDImage) – The input image.
intrinsic (open3d.cpu.pybind.camera.PinholeCameraIntrinsic) – Intrinsic parameters of the camera.
extrinsic (numpy.ndarray[float64[4, 4]], optional) – array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]])
project_valid_depth_only (bool, optional, default=True) –
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
PointCloud.crop(bounding_box, bounding_box)
Function to crop input pointcloud into output pointcloud
- Parameters
bounding_box (open3d.geometry.OrientedBoundingBox) – AxisAlignedBoundingBox to crop points
bounding_box – AxisAlignedBoundingBox to crop points
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
dimension
(self)¶ Returns whether the geometry is 2D or 3D.
- Returns
int
-
estimate_normals
(self, search_param=KDTreeSearchParamKNN with knn = 30, fast_normal_computation=True)¶ Function to compute the normals of a point cloud. Normals are oriented with respect to the input point cloud if normals exist
- Parameters
search_param (open3d.cpu.pybind.geometry.KDTreeSearchParam, optional, default=KDTreeSearchParamKNN with knn = 30) – The KDTree search parameters for neighborhood search.
fast_normal_computation (bool, optional, default=True) – If true, the normal estiamtion uses a non-iterative method to extract the eigenvector from the covariance matrix. This is faster, but is not as numerical stable.
- Returns
None
-
get_axis_aligned_bounding_box
(self)¶ Returns an axis-aligned bounding box of the geometry.
- Returns
open3d.geometry.AxisAlignedBoundingBox
-
get_center
(self)¶ Returns the center of the geometry coordinates.
- Returns
numpy.ndarray[float64[3, 1]]
-
get_geometry_type
(self)¶ Returns one of registered geometry types.
- Returns
open3d.geometry.Geometry.GeometryType
-
get_max_bound
(self)¶ Returns max bounds for geometry coordinates.
- Returns
numpy.ndarray[float64[3, 1]]
-
get_min_bound
(self)¶ Returns min bounds for geometry coordinates.
- Returns
numpy.ndarray[float64[3, 1]]
-
get_oriented_bounding_box
(self)¶ Returns an oriented bounding box of the geometry.
- Returns
open3d.geometry.OrientedBoundingBox
-
static
get_rotation_matrix_from_axis_angle
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_quaternion
(rotation: numpy.ndarray[float64[4, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_xyz
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_xzy
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_yxz
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_yzx
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_zxy
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
static
get_rotation_matrix_from_zyx
(rotation: numpy.ndarray[float64[3, 1]]) → numpy.ndarray[float64[3, 3]]¶
-
has_colors
(self)¶ Returns
True
if the point cloud contains point colors.- Returns
bool
-
has_normals
(self)¶ Returns
True
if the point cloud contains point normals.- Returns
bool
-
has_points
(self)¶ Returns
True
if the point cloud contains points.- Returns
bool
Removes hidden points from a point cloud and returns a mesh of the remaining points. Based on Katz et al. ‘Direct Visibility of Point Sets’, 2007. Additional information about the choice of radius for noisy point clouds can be found in Mehra et. al. ‘Visibility of Noisy Point Cloud Data’, 2010.
- Parameters
camera_location (numpy.ndarray[float64[3, 1]]) – All points not visible from that location will be reomved
radius (float) – The radius of the sperical projection
- Returns
Tuple[open3d.geometry.TriangleMesh, List[int]]
-
is_empty
(self)¶ Returns
True
iff the geometry is empty.- Returns
bool
-
normalize_normals
(self)¶ Normalize point normals to length 1.
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
orient_normals_consistent_tangent_plane
(self, k)¶ Function to orient the normals with respect to consistent tangent planes
- Parameters
k (int) – Number of k nearest neighbors used in constructing the Riemannian graph used to propogate normal orientation.
- Returns
None
-
orient_normals_to_align_with_direction
(self, orientation_reference=array([0.0, 0.0, 1.0]))¶ Function to orient the normals of a point cloud
- Parameters
orientation_reference (numpy.ndarray[float64[3, 1]], optional, default=array([0., 0., 1.])) – Normals are oriented with respect to orientation_reference.
- Returns
None
-
orient_normals_towards_camera_location
(self, camera_location=array([0.0, 0.0, 0.0]))¶ Function to orient the normals of a point cloud
- Parameters
camera_location (numpy.ndarray[float64[3, 1]], optional, default=array([0., 0., 0.])) – Normals are oriented with towards the camera_location.
- Returns
None
-
paint_uniform_color
(self, color)¶ Assigns each point in the PointCloud the same color.
- Parameters
color (numpy.ndarray[float64[3, 1]]) – RGB color for the PointCloud.
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
remove_non_finite_points
(self, remove_nan=True, remove_infinite=True)¶ Function to remove non-finite points from the PointCloud
- Parameters
remove_nan (bool, optional, default=True) – Remove NaN values from the PointCloud
remove_infinite (bool, optional, default=True) – Remove infinite values from the PointCloud
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
remove_radius_outlier
(self, nb_points, radius)¶ Function to remove points that have less than nb_points in a given sphere of a given radius
- Parameters
nb_points (int) – Number of points within the radius.
radius (float) – Radius of the sphere.
- Returns
Tuple[open3d.cpu.pybind.geometry.PointCloud, List[int]]
-
remove_statistical_outlier
(self, nb_neighbors, std_ratio)¶ Function to remove points that are further away from their neighbors in average
- Parameters
nb_neighbors (int) – Number of neighbors around the target point.
std_ratio (float) – Standard deviation ratio.
- Returns
Tuple[open3d.cpu.pybind.geometry.PointCloud, List[int]]
-
PointCloud.rotate(R, R, center)
Apply rotation to the geometry coordinates and normals.
- Parameters
R (numpy.ndarray[float64[3, 3]]) – The rotation matrix
R – The rotation matrix
center (numpy.ndarray[float64[3, 1]]) – Rotation center used for transformation
- Returns
open3d.cpu.pybind.geometry.Geometry3D
-
PointCloud.scale(scale, center, scale, center)
Apply scaling to the geometry coordinates.
- Parameters
scale (float) – The scale parameter that is multiplied to the points/vertices of the geometry
center (numpy.ndarray[float64[3, 1]]) – Scale center used for transformation
scale – The scale parameter that is multiplied to the points/vertices of the geometry
center – Scale center used for transformation
- Returns
open3d.cpu.pybind.geometry.Geometry3D
-
segment_plane
(self, distance_threshold, ransac_n, num_iterations)¶ Segments a plane in the point cloud using the RANSAC algorithm.
- Parameters
distance_threshold (float) – Max distance a point can be from the plane model, and still be considered an inlier.
ransac_n (int) – Number of initial points to be considered inliers in each iteration.
num_iterations (int) – Number of iterations.
- Returns
Tuple[numpy.ndarray[float64[4, 1]], List[int]]
-
select_by_index
(self, indices, invert=False)¶ Function to select points from input pointcloud into output pointcloud.
- Parameters
indices (List[int]) – Indices of points to be selected.
invert (bool, optional, default=False) – Set to
True
to invert the selection of indices.
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
transform
(self, arg0)¶ Apply transformation (4x4 matrix) to the geometry coordinates.
- Parameters
arg0 (numpy.ndarray[float64[4, 4]]) –
- Returns
open3d.cpu.pybind.geometry.Geometry3D
-
translate
(self, translation, relative=True)¶ Apply translation to the geometry coordinates.
- Parameters
translation (numpy.ndarray[float64[3, 1]]) – A 3D vector to transform the geometry
relative (bool, optional, default=True) – If true, the translation vector is directly added to the geometry coordinates. Otherwise, the center is moved to the translation vector.
- Returns
open3d.cpu.pybind.geometry.Geometry3D
-
uniform_down_sample
(self, every_k_points)¶ Function to downsample input pointcloud into output pointcloud uniformly. The sample is performed in the order of the points with the 0-th point always chosen, not at random.
- Parameters
every_k_points (int) – Sample rate, the selected point indices are [0, k, 2k, …]
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
voxel_down_sample
(self, voxel_size)¶ Function to downsample input pointcloud into output pointcloud with a voxel. Normals and colors are averaged if they exist.
- Parameters
voxel_size (float) – Voxel size to downsample into.
- Returns
open3d.cpu.pybind.geometry.PointCloud
-
voxel_down_sample_and_trace
(self, voxel_size, min_bound, max_bound, approximate_class=False)¶ Function to downsample using PointCloud.VoxelDownSample. Also records point cloud index before downsampling
- Parameters
voxel_size (float) – Voxel size to downsample into.
min_bound (numpy.ndarray[float64[3, 1]]) – Minimum coordinate of voxel boundaries
max_bound (numpy.ndarray[float64[3, 1]]) – Maximum coordinate of voxel boundaries
approximate_class (bool, optional, default=False) –
- Returns
Tuple[open3d.cpu.pybind.geometry.PointCloud, numpy.ndarray[int32[m, n]], List[open3d.cpu.pybind.utility.IntVector]]
-
HalfEdgeTriangleMesh
= Type.HalfEdgeTriangleMesh¶
-
Image
= Type.Image¶
-
LineSet
= Type.LineSet¶
-
PointCloud
= Type.PointCloud¶
-
RGBDImage
= Type.RGBDImage¶
-
TetraMesh
= Type.TetraMesh¶
-
TriangleMesh
= Type.TriangleMesh¶
-
Unspecified
= Type.Unspecified¶
-
VoxelGrid
= Type.VoxelGrid¶
-
property
colors
¶ RGB colors of points.
- Type
float64
array of shape(num_points, 3)
, range[0, 1]
, usenumpy.asarray()
to access data
-
property
normals
¶ Points normals.
- Type
float64
array of shape(num_points, 3)
, usenumpy.asarray()
to access data
-
property
points
¶ Points coordinates.
- Type
float64
array of shape(num_points, 3)
, usenumpy.asarray()
to access data
-
class