Open3D (C++ API)  0.19.0
PointCloud.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - Open3D: www.open3d.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.open3d.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <Eigen/Core>
11 #include <memory>
12 #include <optional>
13 #include <tuple>
14 #include <vector>
15 
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;
59  bool robust = false) const;
60  PointCloud &Transform(const Eigen::Matrix4d &transformation) override;
61  PointCloud &Translate(const Eigen::Vector3d &translation,
62  bool relative = true) override;
63  PointCloud &Scale(const double scale,
64  const Eigen::Vector3d &center) override;
65  PointCloud &Rotate(const Eigen::Matrix3d &R,
66  const Eigen::Vector3d &center) override;
67 
68  PointCloud &operator+=(const PointCloud &cloud);
69  PointCloud operator+(const PointCloud &cloud) const;
70 
72  bool HasPoints() const { return points_.size() > 0; }
73 
75  bool HasNormals() const {
76  return points_.size() > 0 && normals_.size() == points_.size();
77  }
78 
80  bool HasColors() const {
81  return points_.size() > 0 && colors_.size() == points_.size();
82  }
83 
85  bool HasCovariances() const {
86  return !points_.empty() && covariances_.size() == points_.size();
87  }
88 
91  for (size_t i = 0; i < normals_.size(); i++) {
92  normals_[i].normalize();
93  }
94  return *this;
95  }
96 
100  PointCloud &PaintUniformColor(const Eigen::Vector3d &color) {
102  return *this;
103  }
104 
113  PointCloud &RemoveNonFinitePoints(bool remove_nan = true,
114  bool remove_infinite = true);
115 
122 
128  std::shared_ptr<PointCloud> SelectByIndex(
129  const std::vector<size_t> &indices, bool invert = false) const;
130 
136  std::shared_ptr<PointCloud> VoxelDownSample(double voxel_size) const;
137 
146  std::tuple<std::shared_ptr<PointCloud>,
147  Eigen::MatrixXi,
148  std::vector<std::vector<int>>>
149  VoxelDownSampleAndTrace(double voxel_size,
150  const Eigen::Vector3d &min_bound,
151  const Eigen::Vector3d &max_bound,
152  bool approximate_class = false) const;
153 
162  std::shared_ptr<PointCloud> UniformDownSample(size_t every_k_points) const;
163 
172  std::shared_ptr<PointCloud> RandomDownSample(double sampling_ratio) const;
173 
182  std::shared_ptr<PointCloud> FarthestPointDownSample(
183  const size_t num_samples, const size_t start_index = 0) const;
184 
192  std::shared_ptr<PointCloud> Crop(const AxisAlignedBoundingBox &bbox,
193  bool invert = false) const;
194 
202  std::shared_ptr<PointCloud> Crop(const OrientedBoundingBox &bbox,
203  bool invert = false) const;
204 
211  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
212  RemoveRadiusOutliers(size_t nb_points,
213  double search_radius,
214  bool print_progress = false) const;
215 
221  std::tuple<std::shared_ptr<PointCloud>, std::vector<size_t>>
222  RemoveStatisticalOutliers(size_t nb_neighbors,
223  double std_ratio,
224  bool print_progress = false) const;
225 
236  void EstimateNormals(
237  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN(),
238  bool fast_normal_computation = true);
239 
245  const Eigen::Vector3d &orientation_reference =
246  Eigen::Vector3d(0.0, 0.0, 1.0));
247 
253  const Eigen::Vector3d &camera_location = Eigen::Vector3d::Zero());
254 
268  const double lambda = 0.0,
269  const double cos_alpha_tol = 1.0);
270 
278  std::vector<double> ComputePointCloudDistance(const PointCloud &target);
279 
288  static std::vector<Eigen::Matrix3d> EstimatePerPointCovariances(
289  const PointCloud &input,
290  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
291 
298  void EstimateCovariances(
299  const KDTreeSearchParam &search_param = KDTreeSearchParamKNN());
300 
303  std::tuple<Eigen::Vector3d, Eigen::Matrix3d> ComputeMeanAndCovariance()
304  const;
305 
310  std::vector<double> ComputeMahalanobisDistance() const;
311 
314  std::vector<double> ComputeNearestNeighborDistance() const;
315 
322  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
323  ComputeConvexHull(bool joggle_inputs = false) const;
324 
335  std::tuple<std::shared_ptr<TriangleMesh>, std::vector<size_t>>
336  HiddenPointRemoval(const Eigen::Vector3d &camera_location,
337  const double radius) const;
338 
350  std::vector<int> ClusterDBSCAN(double eps,
351  size_t min_points,
352  bool print_progress = false) const;
353 
364  std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
365  const double distance_threshold = 0.01,
366  const int ransac_n = 3,
367  const int num_iterations = 100,
368  const double probability = 0.99999999) const;
369 
404  std::vector<std::shared_ptr<OrientedBoundingBox>> DetectPlanarPatches(
405  double normal_variance_threshold_deg = 60,
406  double coplanarity_deg = 75,
407  double outlier_ratio = 0.75,
408  double min_plane_edge_length = 0.0,
409  size_t min_num_points = 0,
410  const geometry::KDTreeSearchParam &search_param =
412 
433  static std::shared_ptr<PointCloud> CreateFromDepthImage(
434  const Image &depth,
435  const camera::PinholeCameraIntrinsic &intrinsic,
436  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
437  double depth_scale = 1000.0,
438  double depth_trunc = 1000.0,
439  int stride = 1,
440  bool project_valid_depth_only = true);
441 
458  static std::shared_ptr<PointCloud> CreateFromRGBDImage(
459  const RGBDImage &image,
460  const camera::PinholeCameraIntrinsic &intrinsic,
461  const Eigen::Matrix4d &extrinsic = Eigen::Matrix4d::Identity(),
462  bool project_valid_depth_only = true);
463 
470  static std::shared_ptr<PointCloud> CreateFromVoxelGrid(
471  const VoxelGrid &voxel_grid);
472 
473 public:
475  std::vector<Eigen::Vector3d> points_;
477  std::vector<Eigen::Vector3d> normals_;
479  std::vector<Eigen::Vector3d> colors_;
481  std::vector<Eigen::Matrix3d> covariances_;
482 };
483 
484 } // namespace geometry
485 } // namespace open3d
std::shared_ptr< core::Tensor > image
Definition: FilamentRenderer.cpp:302
math::float4 color
Definition: LineSetBuffers.cpp:45
Real target
Definition: SurfaceReconstructionPoisson.cpp:267
size_t stride
Definition: TriangleMeshBuffers.cpp:163
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:285
The base geometry class for 3D geometries.
Definition: Geometry3D.h:29
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:138
Definition: BoundingVolume.h:20
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:147
std::vector< Eigen::Vector3d > colors_
RGB colors of points.
Definition: PointCloud.h:479
PointCloud & PaintUniformColor(const Eigen::Vector3d &color)
Definition: PointCloud.h:100
std::vector< Eigen::Matrix3d > covariances_
Covariance Matrix for each point.
Definition: PointCloud.h:481
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:72
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:668
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:710
std::vector< double > ComputePointCloudDistance(const PointCloud &target)
Function to compute the point to point distances between point clouds.
Definition: PointCloud.cpp:130
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:967
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:126
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:755
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:92
bool HasNormals() const
Returns true if the point cloud contains point normals.
Definition: PointCloud.h:75
std::vector< double > ComputeNearestNeighborDistance() const
Definition: PointCloud.cpp:725
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:359
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:187
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:78
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:750
std::tuple< Eigen::Vector3d, Eigen::Matrix3d > ComputeMeanAndCovariance() const
Definition: PointCloud.cpp:700
std::shared_ptr< PointCloud > FarthestPointDownSample(const size_t num_samples, const size_t start_index=0) const
Function to downsample input pointcloud into output pointcloud with a set of points has farthest dist...
Definition: PointCloud.cpp:514
std::shared_ptr< PointCloud > UniformDownSample(size_t every_k_points) const
Function to downsample input pointcloud into output pointcloud uniformly.
Definition: PointCloud.cpp:484
bool HasPoints() const
Returns 'true' if the point cloud contains points.
Definition: PointCloud.h:72
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:222
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:84
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:410
~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:152
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:607
PointCloud & Transform(const Eigen::Matrix4d &transformation) override
Apply transformation (4x4 matrix) to the geometry coordinates.
Definition: PointCloud.cpp:65
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:477
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:552
std::shared_ptr< PointCloud > RandomDownSample(double sampling_ratio) const
Function to downsample input pointcloud into output pointcloud randomly.
Definition: PointCloud.cpp:496
std::vector< Eigen::Vector3d > points_
Points coordinates.
Definition: PointCloud.h:475
void EstimateCovariances(const KDTreeSearchParam &search_param=KDTreeSearchParamKNN())
Function to compute the covariance matrix for each point of a point cloud.
Definition: PointCloud.cpp:694
OrientedBoundingEllipsoid GetOrientedBoundingEllipsoid(bool robust=false) const
Definition: PointCloud.cpp:60
bool HasColors() const
Returns true if the point cloud contains point colors.
Definition: PointCloud.h:80
PointCloud & NormalizeNormals()
Normalize point normals to length 1.
Definition: PointCloud.h:90
bool HasCovariances() const
Returns 'true' if the point cloud contains per-point covariance matrix.
Definition: PointCloud.h:85
bool IsEmpty() const override
Returns true iff the geometry is empty.
Definition: PointCloud.cpp:35
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:574
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
const core::Tensor * indices
Definition: TriangleMesh.cpp:2092