Open3D (C++ API)  0.18.0+5c982c7
PointCloud.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2023 www.open3d.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <Eigen/Core>
11 #include <memory>
12 #include <tuple>
13 #include <vector>
14 
18 
19 namespace open3d {
20 
21 namespace camera {
22 class PinholeCameraIntrinsic;
23 }
24 
25 namespace geometry {
26 
27 class Image;
28 class RGBDImage;
29 class TriangleMesh;
30 class VoxelGrid;
31 
36 class PointCloud : public Geometry3D {
37 public:
43  PointCloud(const std::vector<Eigen::Vector3d> &points)
45  ~PointCloud() override {}
46 
47 public:
48  PointCloud &Clear() override;
49  bool IsEmpty() const override;
50  Eigen::Vector3d GetMinBound() const override;
51  Eigen::Vector3d GetMaxBound() const override;
52  Eigen::Vector3d GetCenter() const override;
55  bool robust = false) const override;
57  bool robust = false) const override;
58  PointCloud &Transform(const Eigen::Matrix4d &transformation) override;
59  PointCloud &Translate(const Eigen::Vector3d &translation,
60  bool relative = true) override;
61  PointCloud &Scale(const double scale,
62  const Eigen::Vector3d &center) override;
63  PointCloud &Rotate(const Eigen::Matrix3d &R,
64  const Eigen::Vector3d &center) override;
65 
66  PointCloud &operator+=(const PointCloud &cloud);
67  PointCloud operator+(const PointCloud &cloud) const;
68 
70  bool HasPoints() const { return points_.size() > 0; }
71 
73  bool HasNormals() const {
74  return points_.size() > 0 && normals_.size() == points_.size();
75  }
76 
78  bool HasColors() const {
79  return points_.size() > 0 && colors_.size() == points_.size();
80  }
81 
83  bool HasCovariances() const {
84  return !points_.empty() && covariances_.size() == points_.size();
85  }
86 
89  for (size_t i = 0; i < normals_.size(); i++) {
90  normals_[i].normalize();
91  }
92  return *this;
93  }
94 
98  PointCloud &PaintUniformColor(const Eigen::Vector3d &color) {
100  return *this;
101  }
102 
111  PointCloud &RemoveNonFinitePoints(bool remove_nan = true,
112  bool remove_infinite = true);
113 
120 
126  std::shared_ptr<PointCloud> SelectByIndex(
127  const std::vector<size_t> &indices, bool invert = false) const;
128 
134  std::shared_ptr<PointCloud> VoxelDownSample(double voxel_size) const;
135 
144  std::tuple<std::shared_ptr<PointCloud>,
145  Eigen::MatrixXi,
146  std::vector<std::vector<int>>>
147  VoxelDownSampleAndTrace(double voxel_size,
148  const Eigen::Vector3d &min_bound,
149  const Eigen::Vector3d &max_bound,
150  bool approximate_class = false) const;
151 
160  std::shared_ptr<PointCloud> UniformDownSample(size_t every_k_points) const;
161 
170  std::shared_ptr<PointCloud> RandomDownSample(double sampling_ratio) const;
171 
179  std::shared_ptr<PointCloud> FarthestPointDownSample(
180  size_t num_samples) const;
181 
189  std::shared_ptr<PointCloud> Crop(const AxisAlignedBoundingBox &bbox,
190  bool invert = false) const;
191 
199  std::shared_ptr<PointCloud> Crop(const OrientedBoundingBox &bbox,
200  bool invert = false) const;
201 
208  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
209  RemoveRadiusOutliers(size_t nb_points,
210  double search_radius,
211  bool print_progress = false) const;
212 
218  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
219  RemoveStatisticalOutliers(size_t nb_neighbors,
220  double std_ratio,
221  bool print_progress = false) const;
222 
233  void EstimateNormals(
234  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN(),
235  bool fast_normal_computation = true);
236 
242  const Eigen::Vector3d &orientation_reference =
243  Eigen::Vector3d(0.0, 0.0, 1.0));
244 
250  const Eigen::Vector3d &camera_location = Eigen::Vector3d::Zero());
251 
265  const double lambda = 0.0,
266  const double cos_alpha_tol = 1.0);
267 
275  std::vector<double> ComputePointCloudDistance(const PointCloud &target);
276 
284  static std::vector<Eigen::Matrix3d> EstimatePerPointCovariances(
285  const PointCloud &input,
286  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
287 
294  void EstimateCovariances(
295  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
296 
299  std::tuple<Eigen::Vector3d, Eigen::Matrix3d> ComputeMeanAndCovariance()
300  const;
301 
306  std::vector<double> ComputeMahalanobisDistance() const;
307 
310  std::vector<double> ComputeNearestNeighborDistance() const;
311 
318  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
319  ComputeConvexHull(bool joggle_inputs = false) const;
320 
330  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
331  HiddenPointRemoval(const Eigen::Vector3d &camera_location,
332  const double radius) const;
333 
345  std::vector<int> ClusterDBSCAN(double eps,
346  size_t min_points,
347  bool print_progress = false) const;
348 
359  std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
360  const double distance_threshold = 0.01,
361  const int ransac_n = 3,
362  const int num_iterations = 100,
363  const double probability = 0.99999999) const;
364 
393  std::vector<std::shared_ptr<OrientedBoundingBox>> DetectPlanarPatches(
394  double normal_variance_threshold_deg = 60,
395  double coplanarity_deg = 75,
396  double outlier_ratio = 0.75,
397  double min_plane_edge_length = 0.0,
398  size_t min_num_points = 0,
399  const geometry::KDTreeSearchParam &search_param =
401 
421  static std::shared_ptr<PointCloud> CreateFromDepthImage(
422  const Image &depth,
423  const camera::PinholeCameraIntrinsic &intrinsic,
424  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
425  double depth_scale = 1000.0,
426  double depth_trunc = 1000.0,
427  int stride = 1,
428  bool project_valid_depth_only = true);
429 
446  static std::shared_ptr<PointCloud> CreateFromRGBDImage(
447  const RGBDImage &image,
448  const camera::PinholeCameraIntrinsic &intrinsic,
449  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
450  bool project_valid_depth_only = true);
451 
458  static std::shared_ptr<PointCloud> CreateFromVoxelGrid(
459  const VoxelGrid &voxel_grid);
460 
461 public:
463  std::vector<Eigen::Vector3d> points_;
465  std::vector<Eigen::Vector3d> normals_;
467  std::vector<Eigen::Vector3d> colors_;
469  std::vector<Eigen::Matrix3d> covariances_;
470 };
471 
472 } // namespace geometry
473 } // namespace open3d
std::shared_ptr< core::Tensor > image
Definition: FilamentRenderer.cpp:183
math::float4 color
Definition: LineSetBuffers.cpp:45
size_t stride
Definition: TriangleMeshBuffers.cpp:165
Contains the pinhole camera intrinsic parameters.
Definition: PinholeCameraIntrinsic.h:32
A bounding box that is aligned along the coordinate axes and defined by the min_bound and max_bound.
Definition: BoundingVolume.h:160
The base geometry class for 3D geometries.
Definition: Geometry3D.h:28
void ResizeAndPaintUniformColor(std::vector< Eigen::Vector3d > &colors, const size_t size, const Eigen::Vector3d &color) const
Resizes the colors vector and paints a uniform color.
Definition: Geometry3D.cpp:56
The base geometry class.
Definition: Geometry.h:18
GeometryType
Specifies possible geometry types.
Definition: Geometry.h:23
The Image class stores image with customizable width, height, num of channels and bytes per channel.
Definition: Image.h:34
Base class for KDTree search parameters.
Definition: KDTreeSearchParam.h:16
KDTree search parameters for pure KNN search.
Definition: KDTreeSearchParam.h:44
A bounding box oriented along an arbitrary frame of reference.
Definition: BoundingVolume.h:25
A point cloud consists of point coordinates, and optionally point colors and point normals.
Definition: PointCloud.h:36
OrientedBoundingBox GetMinimalOrientedBoundingBox(bool robust=false) const override
Definition: PointCloud.cpp:55
std::tuple< Eigen::Vector4d, std::vector< size_t > > SegmentPlane(const double distance_threshold=0.01, const int ransac_n=3, const int num_iterations=100, const double probability=0.99999999) const
Segment PointCloud plane using the RANSAC algorithm.
Definition: PointCloudSegmentation.cpp:150
std::vector< Eigen::Vector3d > colors_
RGB colors of points.
Definition: PointCloud.h:467
PointCloud & PaintUniformColor(const Eigen::Vector3d &color)
Definition: PointCloud.h:98
std::vector< Eigen::Matrix3d > covariances_
Covariance Matrix for each point.
Definition: PointCloud.h:469
void EstimateNormals(const KDTreeSearchParam &search_param=KDTreeSearchParamKNN(), bool fast_normal_computation=true)
Function to compute the normals of a point cloud.
Definition: EstimateNormals.cpp:288
AxisAlignedBoundingBox GetAxisAlignedBoundingBox() const override
Definition: PointCloud.cpp:47
PointCloud & Translate(const Eigen::Vector3d &translation, bool relative=true) override
Apply translation to the geometry coordinates.
Definition: PointCloud.cpp:67
static std::vector< Eigen::Matrix3d > EstimatePerPointCovariances(const PointCloud &input, const KDTreeSearchParam &search_param=KDTreeSearchParamKNN())
Static function to compute the covariance matrix for each point of a point cloud. Doesn't change the ...
Definition: PointCloud.cpp:659
Eigen::Vector3d GetCenter() const override
Returns the center of the geometry coordinates.
Definition: PointCloud.cpp:45
std::vector< double > ComputeMahalanobisDistance() const
Function to compute the Mahalanobis distance for points in an input point cloud.
Definition: PointCloud.cpp:701
std::vector< double > ComputePointCloudDistance(const PointCloud &target)
Function to compute the point to point distances between point clouds.
Definition: PointCloud.cpp:125
std::vector< std::shared_ptr< OrientedBoundingBox > > DetectPlanarPatches(double normal_variance_threshold_deg=60, double coplanarity_deg=75, double outlier_ratio=0.75, double min_plane_edge_length=0.0, size_t min_num_points=0, const geometry::KDTreeSearchParam &search_param=geometry::KDTreeSearchParamKNN()) const
Robustly detect planar patches in the point cloud using. Araújo and Oliveira, “A robust statistics ap...
Definition: PointCloudPlanarPatchDetection.cpp:960
std::vector< int > ClusterDBSCAN(double eps, size_t min_points, bool print_progress=false) const
Cluster PointCloud using the DBSCAN algorithm Ester et al., "A Density-Based Algorithm for Discoverin...
Definition: PointCloudCluster.cpp:20
PointCloud operator+(const PointCloud &cloud) const
Definition: PointCloud.cpp:121
std::tuple< std::shared_ptr< TriangleMesh >, std::vector< size_t > > HiddenPointRemoval(const Eigen::Vector3d &camera_location, const double radius) const
This is an implementation of the Hidden Point Removal operator described in Katz et....
Definition: PointCloud.cpp:746
Eigen::Vector3d GetMinBound() const override
Returns min bounds for geometry coordinates.
Definition: PointCloud.cpp:37
Eigen::Vector3d GetMaxBound() const override
Returns max bounds for geometry coordinates.
Definition: PointCloud.cpp:41
PointCloud & Clear() override
Clear all elements in the geometry.
Definition: PointCloud.cpp:27
PointCloud & operator+=(const PointCloud &cloud)
Definition: PointCloud.cpp:87
bool HasNormals() const
Returns true if the point cloud contains point normals.
Definition: PointCloud.h:73
std::vector< double > ComputeNearestNeighborDistance() const
Definition: PointCloud.cpp:716
std::shared_ptr< PointCloud > VoxelDownSample(double voxel_size) const
Downsample input pointcloud with a voxel, and return a new point-cloud. Normals, covariances and colo...
Definition: PointCloud.cpp:354
PointCloud & RemoveNonFinitePoints(bool remove_nan=true, bool remove_infinite=true)
Removes all points from the point cloud that have a nan entry, or infinite entries....
Definition: PointCloud.cpp:182
PointCloud & Scale(const double scale, const Eigen::Vector3d &center) override
Apply scaling to the geometry coordinates. Given a scaling factor , and center , a given point is tr...
Definition: PointCloud.cpp:73
OrientedBoundingBox GetOrientedBoundingBox(bool robust=false) const override
Definition: PointCloud.cpp:51
static std::shared_ptr< PointCloud > CreateFromDepthImage(const Image &depth, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), double depth_scale=1000.0, double depth_trunc=1000.0, int stride=1, bool project_valid_depth_only=true)
Factory function to create a pointcloud from a depth image and a camera model.
Definition: PointCloudFactory.cpp:130
PointCloud(const std::vector< Eigen::Vector3d > &points)
Parameterized Constructor.
Definition: PointCloud.h:43
std::tuple< std::shared_ptr< TriangleMesh >, std::vector< size_t > > ComputeConvexHull(bool joggle_inputs=false) const
Definition: PointCloud.cpp:741
std::tuple< Eigen::Vector3d, Eigen::Matrix3d > ComputeMeanAndCovariance() const
Definition: PointCloud.cpp:691
std::shared_ptr< PointCloud > UniformDownSample(size_t every_k_points) const
Function to downsample input pointcloud into output pointcloud uniformly.
Definition: PointCloud.cpp:479
bool HasPoints() const
Returns 'true' if the point cloud contains points.
Definition: PointCloud.h:70
std::shared_ptr< PointCloud > SelectByIndex(const std::vector< size_t > &indices, bool invert=false) const
Selects points from input pointcloud, with indices in indices, and returns a new point-cloud with sel...
Definition: PointCloud.cpp:217
void OrientNormalsConsistentTangentPlane(size_t k, const double lambda=0.0, const double cos_alpha_tol=1.0)
Function to consistently orient estimated normals based on consistent tangent planes as described in ...
Definition: EstimateNormals.cpp:362
PointCloud & Rotate(const Eigen::Matrix3d &R, const Eigen::Vector3d &center) override
Apply rotation to the geometry coordinates and normals. Given a rotation matrix , and center ,...
Definition: PointCloud.cpp:79
void OrientNormalsToAlignWithDirection(const Eigen::Vector3d &orientation_reference=Eigen::Vector3d(0.0, 0.0, 1.0))
Function to orient the normals of a point cloud.
Definition: EstimateNormals.cpp:319
std::tuple< std::shared_ptr< PointCloud >, Eigen::MatrixXi, std::vector< std::vector< int > > > VoxelDownSampleAndTrace(double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound, bool approximate_class=false) const
Function to downsample using geometry.PointCloud.VoxelDownSample.
Definition: PointCloud.cpp:405
~PointCloud() override
Definition: PointCloud.h:45
PointCloud & RemoveDuplicatedPoints()
Removes duplicated points, i.e., points that have identical coordinates. It also removes the correspo...
Definition: PointCloud.cpp:147
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > RemoveStatisticalOutliers(size_t nb_neighbors, double std_ratio, bool print_progress=false) const
Function to remove points that are further away from their nb_neighbor neighbors in average.
Definition: PointCloud.cpp:599
PointCloud & Transform(const Eigen::Matrix4d &transformation) override
Apply transformation (4x4 matrix) to the geometry coordinates.
Definition: PointCloud.cpp:60
PointCloud()
Default Constructor.
Definition: PointCloud.h:39
static std::shared_ptr< PointCloud > CreateFromRGBDImage(const RGBDImage &image, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), bool project_valid_depth_only=true)
Factory function to create a pointcloud from an RGB-D image and a camera model.
Definition: PointCloudFactory.cpp:155
static std::shared_ptr< PointCloud > CreateFromVoxelGrid(const VoxelGrid &voxel_grid)
Factory Function to create a PointCloud from a VoxelGrid.
Definition: PointCloudFactory.cpp:180
std::vector< Eigen::Vector3d > normals_
Points normals.
Definition: PointCloud.h:465
void OrientNormalsTowardsCameraLocation(const Eigen::Vector3d &camera_location=Eigen::Vector3d::Zero())
Function to orient the normals of a point cloud.
Definition: EstimateNormals.cpp:338
std::shared_ptr< PointCloud > Crop(const AxisAlignedBoundingBox &bbox, bool invert=false) const
Function to crop pointcloud into output pointcloud.
Definition: PointCloud.cpp:544
std::shared_ptr< PointCloud > RandomDownSample(double sampling_ratio) const
Function to downsample input pointcloud into output pointcloud randomly.
Definition: PointCloud.cpp:491
std::vector< Eigen::Vector3d > points_
Points coordinates.
Definition: PointCloud.h:463
void EstimateCovariances(const KDTreeSearchParam &search_param=KDTreeSearchParamKNN())
Function to compute the covariance matrix for each point of a point cloud.
Definition: PointCloud.cpp:685
bool HasColors() const
Returns true if the point cloud contains point colors.
Definition: PointCloud.h:78
PointCloud & NormalizeNormals()
Normalize point normals to length 1.
Definition: PointCloud.h:88
bool HasCovariances() const
Returns 'true' if the point cloud contains per-point covariance matrix.
Definition: PointCloud.h:83
bool IsEmpty() const override
Returns true iff the geometry is empty.
Definition: PointCloud.cpp:35
std::shared_ptr< PointCloud > FarthestPointDownSample(size_t num_samples) const
Function to downsample input pointcloud into output pointcloud with a set of points has farthest dist...
Definition: PointCloud.cpp:509
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > RemoveRadiusOutliers(size_t nb_points, double search_radius, bool print_progress=false) const
Function to remove points that have less than nb_points in a sphere of a given radius.
Definition: PointCloud.cpp:566
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:27
VoxelGrid is a collection of voxels which are aligned in grid.
Definition: VoxelGrid.h:61
int points
Definition: FilePCD.cpp:54
Definition: PinholeCameraIntrinsic.cpp:16